From 7d7ffff8d7bda867cceb0f1150de515b8dbb6d46 Mon Sep 17 00:00:00 2001 From: Konstantinos Chatzilygeroudis Date: Sat, 31 May 2014 02:04:27 +0300 Subject: [PATCH] Fixed typo in README and added checks in mimic plugin --- README.md | 2 +- src/mimic_joint_plugin.cpp | 24 +++++++++++++++++------- 2 files changed, 18 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 7d0eb32..16f6d21 100644 --- a/README.md +++ b/README.md @@ -32,7 +32,7 @@ A simple (Model) plugin for Gazebo that allows you to disable a link in Gazebo's - link (Required) - A **string** specifying the name of the link to be disable. It should be a valid sdf (not urdf) link. + A **string** specifying the name of the link to be disabled. It should be a valid sdf (not urdf) link. ###Hoping to add more plugins.... diff --git a/src/mimic_joint_plugin.cpp b/src/mimic_joint_plugin.cpp index f3aa770..979912f 100644 --- a/src/mimic_joint_plugin.cpp +++ b/src/mimic_joint_plugin.cpp @@ -45,7 +45,7 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ) this->world_ = this->model_->GetWorld(); // Check for joint element - if (!_sdf->HasElement("joint")) + if(!_sdf->HasElement("joint")) { ROS_ERROR("No joint element present. MimicJointPlugin could not be loaded."); return; @@ -54,7 +54,7 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ) joint_name_ = _sdf->GetElement("joint")->Get(); // Check for mimicJoint element - if (!_sdf->HasElement("mimicJoint")) + if(!_sdf->HasElement("mimicJoint")) { ROS_ERROR("No mimicJoint element present. MimicJointPlugin could not be loaded."); return; @@ -64,7 +64,7 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ) // Check for multiplier element multiplier_ = 1.0; - if (_sdf->HasElement("multiplier")) + if(_sdf->HasElement("multiplier")) multiplier_ = _sdf->GetElement("multiplier")->Get(); // Check for offset element @@ -72,14 +72,24 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ) if (_sdf->HasElement("offset")) offset_ = _sdf->GetElement("offset")->Get(); + // Get pointers to joints + joint_ = model_->GetJoint(joint_name_); + if(!joint_) + { + ROS_ERROR("No joint named %s. MimicJointPlugin could not be loaded.", joint_name_.c_str()); + return; + } + mimic_joint_ = model_->GetJoint(mimic_joint_name_); + if(!mimic_joint_) + { + ROS_ERROR("No (mimic) joint named %s. MimicJointPlugin could not be loaded.", mimic_joint_name_.c_str()); + return; + } + // Listen to the update event. This event is broadcast every // simulation iteration. this->updateConnection = event::Events::ConnectWorldUpdateBegin( boost::bind(&MimicJointPlugin::UpdateChild, this)); - - // Get pointers to joints - joint_ = model_->GetJoint(joint_name_); - mimic_joint_ = model_->GetJoint(mimic_joint_name_); } void MimicJointPlugin::UpdateChild() -- 2.12.0