-
Notifications
You must be signed in to change notification settings - Fork 773
ROS 2 Migration: F3D
Leander Stephen D'Souza edited this page Jun 26, 2022
·
2 revisions
F3D and FTSensor plugins from ROS1 have been merged into gazebo_ros_ft_sensor
in ROS2. This pages contains instructions on how to use FTSensor in ROS2 as F3D plugin in gazebo_plugins
in ROS1.
- All SDF parameters are now
snake_cased
. - If the topic name is not defined, default to
wrench
instead of failing. -
tf_prefix
is no longer supported. - Additional support for modifying update rate and adding Gaussian noise to the sensor readings.
ROS 1 | ROS 2 |
---|---|
robotNamespace |
<ros><namespace> |
bodyName |
body_name |
topicName |
<ros><remapping>wrench:=custom_wrench</remapping></ros> |
frameName |
frame_name |
<model name='the_model'>
...
<link name='box_link'>
...
</link>
<plugin name="gazebo_ros_f3d" filename="libgazebo_ros_f3d.so">
<robotNamespace>demo</robotNamespace>
<topicName>f3d_demo</topicName>
<bodyName>box_link</bodyName>
</plugin>
</model>
<model name='the_model'>
...
<link name='box_link'>
...
</link>
<plugin name="gazebo_ros_f3d" filename="libgazebo_ros_ft_sensor.so">
<ros>
<!-- Add namespace and remap the default topic -->
<namespace>/demo</namespace>
<remapping>wrench:=f3d_demo</remapping>
</ros>
<!-- Set update rate-->
<update_rate>200</update_rate>
<!-- Replace camelCase elements with camel_case ones -->
<body_name>box_link</body_name>
<frame_name>sphere_link</frame_name>
<update_rate>1</update_rate>
<!-- Add Gaussian noise -->
<gaussian_noise>0.01</gaussian_noise>
</plugin>
</model>