44#include " gazebo_ros_link_attacher/Attach.h"
55#include " gazebo_ros_link_attacher/AttachRequest.h"
66#include " gazebo_ros_link_attacher/AttachResponse.h"
7+ #include < ignition/math/Pose3.hh>
78
89namespace gazebo
910{
@@ -33,7 +34,11 @@ namespace gazebo
3334 }
3435
3536 this ->world = _world;
36- this ->physics = this ->world ->GetPhysicsEngine ();
37+ #if GAZEBO_VERSION_MAJOR > 7
38+ this ->physics = this ->world ->Physics ();
39+ #else
40+ this ->physics = this ->world ->GetPhysicsEngine ();
41+ #endif
3742 this ->attach_service_ = this ->nh_ .advertiseService (" attach" , &GazeboRosLinkAttacher::attach_callback, this );
3843 ROS_INFO_STREAM (" Attach service at: " << this ->nh_ .resolveName (" attach" ));
3944 this ->detach_service_ = this ->nh_ .advertiseService (" detach" , &GazeboRosLinkAttacher::detach_callback, this );
@@ -63,13 +68,22 @@ namespace gazebo
6368 j.model2 = model2;
6469 j.link2 = link2;
6570 ROS_DEBUG_STREAM (" Getting BasePtr of " << model1);
66- physics::BasePtr b1 = this ->world ->GetByName (model1);
71+ #if GAZEBO_VERSION_MAJOR > 7
72+ physics::BasePtr b1 = this ->world ->ModelByName (model1);
73+ #else
74+ physics::BasePtr b1 = this ->world ->GetModel (model1);
75+ #endif
6776 if (b1 == NULL ){
6877 ROS_ERROR_STREAM (model1 << " model was not found" );
6978 return false ;
7079 }
80+
7181 ROS_DEBUG_STREAM (" Getting BasePtr of " << model2);
72- physics::BasePtr b2 = this ->world ->GetByName (model2);
82+ #if GAZEBO_VERSION_MAJOR > 7
83+ physics::BasePtr b2 = this ->world ->ModelByName (model2);
84+ #else
85+ physics::BasePtr b2 = this ->world ->GetModel (model2);
86+ #endif
7387 if (b2 == NULL ){
7488 ROS_ERROR_STREAM (model2 << " model was not found" );
7589 return false ;
@@ -91,8 +105,13 @@ namespace gazebo
91105 ROS_ERROR_STREAM (" link1 inertia is NULL!" );
92106 }
93107 else
108+ #if GAZEBO_VERSION_MAJOR > 7
109+ ROS_DEBUG_STREAM (" link1 inertia is not NULL, for example, mass is: " << l1->GetInertial ()->Mass ());
110+ #else
94111 ROS_DEBUG_STREAM (" link1 inertia is not NULL, for example, mass is: " << l1->GetInertial ()->GetMass ());
112+ #endif
95113 j.l1 = l1;
114+
96115 ROS_DEBUG_STREAM (" Getting link: '" << link2 << " ' from model: '" << model2 << " '" );
97116 physics::LinkPtr l2 = m2->GetLink (link2);
98117 if (l2 == NULL ){
@@ -103,7 +122,11 @@ namespace gazebo
103122 ROS_ERROR_STREAM (" link2 inertia is NULL!" );
104123 }
105124 else
125+ #if GAZEBO_VERSION_MAJOR > 7
126+ ROS_DEBUG_STREAM (" link2 inertia is not NULL, for example, mass is: " << l2->GetInertial ()->Mass ());
127+ #else
106128 ROS_DEBUG_STREAM (" link2 inertia is not NULL, for example, mass is: " << l2->GetInertial ()->GetMass ());
129+ #endif
107130 j.l2 = l2;
108131
109132 ROS_DEBUG_STREAM (" Links are: " << l1->GetName () << " and " << l2->GetName ());
@@ -115,7 +138,7 @@ namespace gazebo
115138 ROS_DEBUG_STREAM (" Attach" );
116139 j.joint ->Attach (l1, l2);
117140 ROS_DEBUG_STREAM (" Loading links" );
118- j.joint ->Load (l1, l2, math::Pose ());
141+ j.joint ->Load (l1, l2, ignition:: math::Pose3d ());
119142 ROS_DEBUG_STREAM (" SetModel" );
120143 j.joint ->SetModel (m2);
121144 /*
@@ -133,9 +156,9 @@ namespace gazebo
133156 */
134157
135158 ROS_DEBUG_STREAM (" SetHightstop" );
136- j.joint ->SetHighStop (0 , 0 );
159+ j.joint ->SetUpperLimit (0 , 0 );
137160 ROS_DEBUG_STREAM (" SetLowStop" );
138- j.joint ->SetLowStop (0 , 0 );
161+ j.joint ->SetLowerLimit (0 , 0 );
139162 ROS_DEBUG_STREAM (" Init" );
140163 j.joint ->Init ();
141164 ROS_INFO_STREAM (" Attach finished." );
0 commit comments