-
Notifications
You must be signed in to change notification settings - Fork 5
Using
ivan1993br edited this page Oct 24, 2018
·
2 revisions
How to insert it on your xacro.
First lets supose you have a link called my_link
as showed down here:
<link name="my_link">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.01" ixy="0.001" ixz="0.001" iyy="0.01" iyz="0.001" izz="0.01"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 ${pi/2} 0"/>
<geometry>
<cylinder length="0.2" radius="0.1"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
Then you need to do two main things:
-
Set the gazebo reference as this link or some link on your robot:
<gazebo reference="my_link">
-
Set the link reference as this link:
<link_reference>my_link</link_reference>
Then you should have something like that:
<gazebo reference="my_link"> <sensor name='my_sonar' type='camera'> <plugin name="my_sonar_controller" filename="libFowardLookingGazeboSonar.so" > <topic>my_model/FLSonar</topic> <debug>1</debug> <link_reference>my_link</link_reference> <horizontal_fov>${pi/2}</horizontal_fov> <vfov>${pi/4}</vfov> <bin_count>720</bin_count> <beam_count>720</beam_count> <image> <width>720</width> <height>720</height> <format>R32G32B32</format> </image> <clip> <near>0.1</near> <far>5</far> </clip> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.1</stddev> </noise> </plugin> </sensor> </gazebo>
Brazilian Institute of Robotics (c) 2018