@@ -34,7 +34,6 @@ I'm not sure exactly where the dependency chain includes PID.hh for the first ti
34
34
#define private public
35
35
#include < gazebo/common/Plugin.hh>
36
36
#include < gazebo/common/Time.hh>
37
- #include < gazebo/math/Angle.hh>
38
37
#include < gazebo/physics/physics.hh>
39
38
#include < robotiq_3f_gripper_articulated_gazebo_plugins/RobotiqHandPlugin.h>
40
39
#undef private
@@ -69,7 +68,9 @@ RobotiqHandPlugin::RobotiqHandPlugin()
69
68
// //////////////////////////////////////////////////////////////////////////////
70
69
RobotiqHandPlugin::~RobotiqHandPlugin ()
71
70
{
71
+ #if GAZEBO_MAJOR_VERSION < 9
72
72
gazebo::event::Events::DisconnectWorldUpdateBegin (this ->updateConnection );
73
+ #endif
73
74
this ->rosNode ->shutdown ();
74
75
this ->rosQueue .clear ();
75
76
this ->rosQueue .disable ();
@@ -204,7 +205,11 @@ void RobotiqHandPlugin::Load(gazebo::physics::ModelPtr _parent,
204
205
this ->subHandleCommand = this ->rosNode ->subscribe (handleCommandSo);
205
206
206
207
// Controller time control.
208
+ #if GAZEBO_MAJOR_VERSION >= 9
209
+ this ->lastControllerUpdateTime = this ->world ->SimTime ();
210
+ #else
207
211
this ->lastControllerUpdateTime = this ->world ->GetSimTime ();
212
+ #endif
208
213
209
214
// Start callback queue.
210
215
this ->callbackQueueThread =
@@ -322,14 +327,22 @@ bool RobotiqHandPlugin::IsHandFullyOpen()
322
327
323
328
// The hand will be fully open when all the fingers are within 'tolerance'
324
329
// from their lower limits.
330
+ #if GAZEBO_MAJOR_VERSION >= 9
331
+ ignition::math::Angle tolerance;
332
+ tolerance.Degree (1.0 );
333
+ #else
325
334
gazebo::math::Angle tolerance;
326
335
tolerance.SetFromDegree (1.0 );
336
+ #endif
327
337
328
338
for (int i = 2 ; i < this ->NumJoints ; ++i)
329
339
{
330
340
fingersOpen = fingersOpen &&
331
- (this ->joints [i]->GetAngle (0 ) <
332
- (this ->joints [i]->GetLowerLimit (0 ) + tolerance));
341
+ #if GAZEBO_MAJOR_VERSION >= 9
342
+ (this ->joints [i]->Position (0 ) < (this ->joints [i]->LowerLimit (0 ) + tolerance ()));
343
+ #else
344
+ (this ->joints [i]->GetAngle (0 ) < (this ->joints [i]->GetLowerLimit (0 ) + tolerance));
345
+ #endif
333
346
}
334
347
335
348
return fingersOpen;
@@ -339,8 +352,11 @@ bool RobotiqHandPlugin::IsHandFullyOpen()
339
352
void RobotiqHandPlugin::UpdateStates ()
340
353
{
341
354
boost::mutex::scoped_lock lock (this ->controlMutex );
342
-
355
+ #if GAZEBO_MAJOR_VERSION >= 9
356
+ gazebo::common::Time curTime = this ->world ->SimTime ();
357
+ #else
343
358
gazebo::common::Time curTime = this ->world ->GetSimTime ();
359
+ #endif
344
360
345
361
// Step 1: State transitions.
346
362
if (curTime > this ->lastControllerUpdateTime )
@@ -507,18 +523,28 @@ uint8_t RobotiqHandPlugin::GetCurrentPosition(
507
523
const gazebo::physics::JointPtr &_joint)
508
524
{
509
525
// Full range of motion.
510
- gazebo::math::Angle range =
511
- _joint->GetUpperLimit (0 ) - _joint->GetLowerLimit (0 );
526
+ #if GAZEBO_MAJOR_VERSION >= 9
527
+ ignition::math::Angle range = _joint->UpperLimit (0 ) - _joint->LowerLimit (0 );
528
+ #else
529
+ gazebo::math::Angle range = _joint->GetUpperLimit (0 ) - _joint->GetLowerLimit (0 );
530
+ #endif
512
531
513
532
// The maximum value in pinch mode is 177.
514
533
if (this ->graspingMode == Pinch)
515
534
range *= 177.0 / 255.0 ;
516
535
517
536
// Angle relative to the lower limit.
537
+ #if GAZEBO_MAJOR_VERSION >= 9
538
+ ignition::math::Angle relAngle = _joint->Position (0 ) - _joint->LowerLimit (0 );
539
+ #else
518
540
gazebo::math::Angle relAngle = _joint->GetAngle (0 ) - _joint->GetLowerLimit (0 );
541
+ #endif
519
542
520
- return
521
- static_cast <uint8_t >(round (255.0 * relAngle.Radian () / range.Radian ()));
543
+ #if GAZEBO_MAJOR_VERSION >= 9
544
+ return static_cast <uint8_t >(round (255.0 * relAngle () / range ()));
545
+ #else
546
+ static_cast <uint8_t >(round (255.0 * relAngle.Radian () / range.Radian ()));
547
+ #endif
522
548
}
523
549
524
550
// //////////////////////////////////////////////////////////////////////////////
@@ -645,7 +671,11 @@ void RobotiqHandPlugin::GetAndPublishJointState(
645
671
this ->jointStates .header .stamp = ros::Time (_curTime.sec , _curTime.nsec );
646
672
for (size_t i = 0 ; i < this ->joints .size (); ++i)
647
673
{
674
+ #if GAZEBO_MAJOR_VERSION >= 9
675
+ this ->jointStates .position [i] = this ->joints [i]->Position (0 );
676
+ #else
648
677
this ->jointStates .position [i] = this ->joints [i]->GetAngle (0 ).Radian ();
678
+ #endif
649
679
this ->jointStates .velocity [i] = this ->joints [i]->GetVelocity (0 );
650
680
// better to use GetForceTorque dot joint axis
651
681
this ->jointStates .effort [i] = this ->joints [i]->GetForce (0u );
@@ -674,7 +704,11 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
674
704
switch (this ->graspingMode )
675
705
{
676
706
case Wide:
707
+ #if GAZEBO_MAJOR_VERSION >= 9
708
+ targetPose = this ->joints [i]->UpperLimit (0 );
709
+ #else
677
710
targetPose = this ->joints [i]->GetUpperLimit (0 ).Radian ();
711
+ #endif
678
712
break ;
679
713
680
714
case Pinch:
@@ -684,9 +718,15 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
684
718
685
719
case Scissor:
686
720
// Max position is reached at value 215.
721
+ #if GAZEBO_MAJOR_VERSION >= 9
722
+ targetPose = this ->joints [i]->UpperLimit (0 ) -
723
+ (this ->joints [i]->UpperLimit (0 ) -
724
+ this ->joints [i]->LowerLimit (0 )) * (215.0 / 255.0 )
725
+ #else
687
726
targetPose = this ->joints [i]->GetUpperLimit (0 ).Radian () -
688
727
(this ->joints [i]->GetUpperLimit (0 ).Radian () -
689
728
this ->joints [i]->GetLowerLimit (0 ).Radian ()) * (215.0 / 255.0 )
729
+ #endif
690
730
* this ->handleCommand .rPRA / 255.0 ;
691
731
break ;
692
732
}
@@ -696,7 +736,11 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
696
736
switch (this ->graspingMode )
697
737
{
698
738
case Wide:
739
+ #if GAZEBO_MAJOR_VERSION >= 9
740
+ targetPose = this ->joints [i]->LowerLimit (0 );
741
+ #else
699
742
targetPose = this ->joints [i]->GetLowerLimit (0 ).Radian ();
743
+ #endif
700
744
break ;
701
745
702
746
case Pinch:
@@ -706,9 +750,15 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
706
750
707
751
case Scissor:
708
752
// Max position is reached at value 215.
753
+ #if GAZEBO_MAJOR_VERSION >= 9
754
+ targetPose = this ->joints [i]->LowerLimit (0 ) +
755
+ (this ->joints [i]->UpperLimit (0 ) -
756
+ this ->joints [i]->LowerLimit (0 )) * (215.0 / 255.0 )
757
+ #else
709
758
targetPose = this ->joints [i]->GetLowerLimit (0 ).Radian () +
710
759
(this ->joints [i]->GetUpperLimit (0 ).Radian () -
711
760
this ->joints [i]->GetLowerLimit (0 ).Radian ()) * (215.0 / 255.0 )
761
+ #endif
712
762
* this ->handleCommand .rPRA / 255.0 ;
713
763
break ;
714
764
}
@@ -718,9 +768,15 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
718
768
if (this ->graspingMode == Pinch)
719
769
{
720
770
// Max position is reached at value 177.
771
+ #if GAZEBO_MAJOR_VERSION >= 9
772
+ targetPose = this ->joints [i]->LowerLimit (0 ) +
773
+ (this ->joints [i]->UpperLimit (0 ) -
774
+ this ->joints [i]->LowerLimit (0 )) * (177.0 / 255.0 )
775
+ #else
721
776
targetPose = this ->joints [i]->GetLowerLimit (0 ).Radian () +
722
777
(this ->joints [i]->GetUpperLimit (0 ).Radian () -
723
778
this ->joints [i]->GetLowerLimit (0 ).Radian ()) * (177.0 / 255.0 )
779
+ #endif
724
780
* this ->handleCommand .rPRA / 255.0 ;
725
781
}
726
782
else if (this ->graspingMode == Scissor)
@@ -731,15 +787,25 @@ void RobotiqHandPlugin::UpdatePIDControl(double _dt)
731
787
}
732
788
else
733
789
{
790
+ #if GAZEBO_MAJOR_VERSION >= 9
791
+ targetPose = this ->joints [i]->LowerLimit (0 ) +
792
+ (this ->joints [i]->UpperLimit (0 ) -
793
+ this ->joints [i]->LowerLimit (0 ))
794
+ #else
734
795
targetPose = this ->joints [i]->GetLowerLimit (0 ).Radian () +
735
796
(this ->joints [i]->GetUpperLimit (0 ).Radian () -
736
797
this ->joints [i]->GetLowerLimit (0 ).Radian ())
798
+ #endif
737
799
* this ->handleCommand .rPRA / 255.0 ;
738
800
}
739
801
}
740
802
741
803
// Get the current pose.
804
+ #if GAZEBO_MAJOR_VERSION >= 9
805
+ double currentPose = this ->joints [i]->Position (0 );
806
+ #else
742
807
double currentPose = this ->joints [i]->GetAngle (0 ).Radian ();
808
+ #endif
743
809
744
810
// Position error.
745
811
double poseError = currentPose - targetPose;
0 commit comments