Skip to content

Commit

Permalink
Adjust to Gazebo 8 API
Browse files Browse the repository at this point in the history
Note about the DisconnectWorldUpdateBegin: This function was deprecated
in favor of resetting the ConnectionPtr, see here:

    https://bitbucket.org/osrf/gazebo/pull-requests/2329/deprecate-event-disconnect-connectionptr/diff
  • Loading branch information
mintar committed Mar 16, 2018
1 parent cdb9bca commit 901ddbf
Showing 1 changed file with 19 additions and 5 deletions.
24 changes: 19 additions & 5 deletions src/mimic_joint_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,12 @@ OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISE

#include <roboticsgroup_gazebo_plugins/mimic_joint_plugin.h>

#if GAZEBO_MAJOR_VERSION >= 8
using namespace ignition::math;
#else
using namespace gazebo::math;
#endif

namespace gazebo {

MimicJointPlugin::MimicJointPlugin()
Expand All @@ -34,8 +40,7 @@ namespace gazebo {

MimicJointPlugin::~MimicJointPlugin()
{
event::Events::DisconnectWorldUpdateBegin(this->updateConnection);

this->updateConnection.reset();
kill_sim = true;
}

Expand Down Expand Up @@ -143,18 +148,27 @@ namespace gazebo {

void MimicJointPlugin::UpdateChild()
{
#if GAZEBO_MAJOR_VERSION >= 8
static ros::Duration period(world_->Physics()->GetMaxStepSize());
#else
static ros::Duration period(world_->GetPhysicsEngine()->GetMaxStepSize());
#endif

// Set mimic joint's angle based on joint's angle
#if GAZEBO_MAJOR_VERSION >= 8
double angle = joint_->Position(0) * multiplier_ + offset_;
double a = mimic_joint_->Position(0);
#else
double angle = joint_->GetAngle(0).Radian() * multiplier_ + offset_;
double a = mimic_joint_->GetAngle(0).Radian();
#endif

if (abs(angle - mimic_joint_->GetAngle(0).Radian()) >= sensitiveness_) {
if (abs(angle - a) >= sensitiveness_) {
if (has_pid_) {
double a = mimic_joint_->GetAngle(0).Radian();
if (a != a)
a = angle;
double error = angle - a;
double effort = gazebo::math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_);
double effort = clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_);
mimic_joint_->SetForce(0, effort);
}
else {
Expand Down

0 comments on commit 901ddbf

Please sign in to comment.