-
Notifications
You must be signed in to change notification settings - Fork 773
ROS 2 Migration: Harness
Leander Stephen D'Souza edited this page Jun 26, 2022
·
2 revisions
This pages describes the changes in the harness plugin in gazebo_plugins
for ROS 2, including a migration guide.
- Instead of using
std_msgs/msg/Bool
for detach messages and checking for truth value, detach messages are nowstd_msgs/msg/Empty
. On receiving the message, without any checks, the joint would be detached. - Harness topics can now be changed using remapping arguments.
- By setting the
<init_vel>
in sdf, the initial velocity of harness on launching gazebo can be set.
ROS 1 | ROS 2 |
---|---|
robotNamespace |
❌ |
<plugin name="plugin_name" filename="libgazebo_ros_harness.so">
<!-- Add a namespace -->
<robotNamespace>demo</robotNamespace>
<joint name="joint1" type="prismatic">
<pose>0 0 0 0 0 0</pose>
<parent>world</parent>
<child>link</child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>10</damping>
</dynamics>
<limit>
<lower>-1.5</lower>
<upper>1.5</upper>
<effort>10000</effort>
<velocity>-1</velocity>
<stiffness>0</stiffness>
<dissipation>0</dissipation>
</limit>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
<limit>
<cfm>0.0</cfm>
<erp>0.0</erp>
</limit>
</ode>
</physics>
</joint>
<!-- The joint that raises or lowers the harness -->
<winch>
<!-- This must be a joint specified within
the body of this plugin. -->
<joint>joint1</joint>
<!-- PID value for velocity control of the winch -->
<pos_pid>
<p>1000000</p>
<i>0</i>
<d>0</d>
<i_min>0</i_min>
<i_max>0</i_max>
<cmd_min>-10000</cmd_min>
<cmd_max>10000</cmd_max>
</pos_pid>
<vel_pid>
<p>10000</p>
<i>0</i>
<d>0</d>
<i_min>0</i_min>
<i_max>0</i_max>
<cmd_min>0</cmd_min>
<cmd_max>10000</cmd_max>
</vel_pid>
</winch>
<!-- Joint to detach. Once the joint is detached, it cannot be
reattached. This must be a joint specified within the
body of this plugin. -->
<detach>joint1</detach>
</plugin>
<plugin name="plugin_name" filename="libgazebo_ros_harness.so">
<ros>
<!-- Add a namespace -->
<namespace>demo</namespace>
<!-- Default harness velocity topic `${MODEL_NAME}/harness/velocity` can be changed -->
<!-- Here it is set to `/demo/velocity_demo` -->
<remapping>box/harness/velocity:=velocity_demo</remapping>
<!-- Default harness detach topic `${MODEL_NAME}/harness/detach` can be changed -->
<!-- Here it is set to `/demo/detach_demo` -->
<remapping>box/harness/detach:=detach_demo</remapping>
</ros>
<!-- set initial harness velocity -->
<init_vel>-0.1</init_vel>
<joint name="joint1" type="prismatic">
<!-- The joint that raises or lowers the harness.
This must be specified within the body of this plugin. -->
<pose>0 0 0 0 0 0</pose>
<parent>world</parent>
<child>link</child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>10</damping>
</dynamics>
<limit>
<lower>-1.5</lower>
<upper>1.5</upper>
<effort>10000</effort>
<velocity>-1</velocity>
<stiffness>0</stiffness>
<dissipation>0</dissipation>
</limit>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
<limit>
<cfm>0.0</cfm>
<erp>0.0</erp>
</limit>
</ode>
</physics>
</joint>
<winch>
<joint>joint1</joint>
<!-- PID value for velocity control of the winch. -->
<pos_pid>
<p>1000000</p>
<i>0</i>
<d>0</d>
<i_min>0</i_min>
<i_max>0</i_max>
<cmd_min>-10000</cmd_min>
<cmd_max>10000</cmd_max>
</pos_pid>
<vel_pid>
<p>10000</p>
<i>0</i>
<d>0</d>
<i_min>0</i_min>
<i_max>0</i_max>
<cmd_min>0</cmd_min>
<cmd_max>10000</cmd_max>
</vel_pid>
</winch>
<!-- Joint to detach. Once the joint is detached, it cannot be
reattached. This must be a joint specified within the
body of this plugin. -->
<detach>joint1</detach>
</plugin>