Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 4 additions & 10 deletions vrx_urdf/wamv_gazebo/urdf/components/wamv_pinger.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,19 +4,13 @@
<link name="${namespace}/${name}">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
</visual>
<collision name="${name}_collision">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.00000542" ixy="0.0" ixz="0.0" iyy="0.00002104" iyz="0.0" izz="0.00002604"/>
</inertial>
</link>
<joint name="${namespace}/${name}_pinger_joint" type="fixed">
<origin xyz="${position}" rpy="${orientation}"/>
<parent link="${namespace}/base_link"/>
<child link="${namespace}/${name}"/>
</joint>
Expand Down
28 changes: 26 additions & 2 deletions vrx_urdf/wamv_gazebo/urdf/wamv_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,32 @@
<!-- === Decide if we lock the robot to the world === -->
<xacro:if value="$(arg locked)">
<gazebo>
<link name="wamv_external_link"/>
<link name="wamv_external_link_base"/>
<link name="wamv_external_link">
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.00000004</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00000004</iyy>
<iyz>0</iyz>
<izz>0.00000004</izz>
</inertia>
</inertial>
</link>
<link name="wamv_external_link_base">
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.00000004</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00000004</iyy>
<iyz>0</iyz>
<izz>0.00000004</izz>
</inertia>
</inertial>
</link>
<joint name="wamv_external_pivot_joint" type="universal">
<parent>wamv_external_link</parent>
<child>wamv/base_link</child>
Expand Down