103 lines
2.5 KiB
XML
103 lines
2.5 KiB
XML
<?xml version="1.0" ?>
|
|
<robot name="rm_65_description">
|
|
<link name="root"/>
|
|
|
|
<link name="base_link">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.000433277303987328 -3.54664423471128E-05 0.0599427668933796"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.841070778135659" />
|
|
<inertia
|
|
ixx="0.0017261110801622"
|
|
ixy="2.52746264980217E-06"
|
|
ixz="-3.67690303614961E-05"
|
|
iyy="0.00170987405835604"
|
|
iyz="1.67996364994424E-06"
|
|
izz="0.000904023422915791" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/base_link.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="1 1 1 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/base_link.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<link name="link_1">
|
|
<inertial>
|
|
<origin
|
|
xyz="1.2226305431569E-08 0.0211079974844683 -0.0251854220842269"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.593563443690403" />
|
|
<inertia
|
|
ixx="0.00126614120341847"
|
|
ixy="-1.294980943835E-08"
|
|
ixz="-9.80120923066996E-09"
|
|
iyy="0.00118168178300364"
|
|
iyz="-0.00021121727444415"
|
|
izz="0.00056135241627747" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link1.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="1 1 1 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link1.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint name="root_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="root"/>
|
|
<child link="base_link"/>
|
|
</joint>
|
|
|
|
<joint name="joint1" type="revolute">
|
|
<parent link="base_link" />
|
|
<child link="link_1" />
|
|
<axis xyz="0 0 1" />
|
|
<origin xyz="0 0 0.2405" rpy="0 0 0" />
|
|
<limit
|
|
lower="-3.1"
|
|
upper="3.1"
|
|
effort="60"
|
|
velocity="3.14" />
|
|
</joint>
|
|
</robot>
|