Skip to content

Commit

Permalink
fixed gripper cpp
Browse files Browse the repository at this point in the history
  • Loading branch information
filesmuggler committed Mar 9, 2020
1 parent d6be319 commit 70fd72e
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions robotiq_gazebo/src/mimic_joint_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ MimicJointPlugin::MimicJointPlugin()

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

//event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
this->updateConnection.reset();
kill_sim = true;
}

Expand Down Expand Up @@ -167,20 +167,20 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf )

void MimicJointPlugin::UpdateChild()
{
static ros::Duration period(world_->GetPhysicsEngine()->GetMaxStepSize());
static ros::Duration period(world_->Physics()->GetMaxStepSize());

// Set mimic joint's angle based on joint's angle
double angle = joint_->GetAngle(0).Radian()*multiplier_+offset_;
double angle = joint_->Position(0)*multiplier_+offset_;

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

0 comments on commit 70fd72e

Please sign in to comment.