400 lines
9.7 KiB
XML
400 lines
9.7 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<robot
|
|
name="rm_65_description">
|
|
<link name="root"/>
|
|
<joint name="root_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="root"/>
|
|
<child link="base_link"/>
|
|
</joint>
|
|
<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="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>
|
|
<link
|
|
name="link_2">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.152256463426163 4.75383656106654E-07 -0.00620260383607792"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.864175046869043" />
|
|
<inertia
|
|
ixx="0.00089150298478414"
|
|
ixy="-2.23268489334765E-08"
|
|
ixz="0.00156246461035015"
|
|
iyy="0.00733754343083901"
|
|
iyz="6.28110889329165E-09"
|
|
izz="0.00697869103915473" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link2.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/link2.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="joint2"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="1.5708 -1.5708 0" />
|
|
<parent
|
|
link="link_1" />
|
|
<child
|
|
link="link_2" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="-2.268"
|
|
upper="2.268"
|
|
effort="60"
|
|
velocity="3.14" />
|
|
</joint>
|
|
<link
|
|
name="link_3">
|
|
<inertial>
|
|
<origin
|
|
xyz="5.05312670989961E-06 -0.0595925663694732 0.010569069212336"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.289633681624654" />
|
|
<inertia
|
|
ixx="0.00063737100450158"
|
|
ixy="-7.05261293649751E-08"
|
|
ixz="-3.86643272239426E-08"
|
|
iyy="0.00015648388095025"
|
|
iyz="-0.00014461035994916"
|
|
izz="0.000614178164773085" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link3.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/link3.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="joint3"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.256 0 0"
|
|
rpy="0 0 1.5708" />
|
|
<parent
|
|
link="link_2" />
|
|
<child
|
|
link="link_3" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="-2.355"
|
|
upper="2.355"
|
|
effort="30"
|
|
velocity="3.92" />
|
|
</joint>
|
|
<link
|
|
name="link_4">
|
|
<inertial>
|
|
<origin
|
|
xyz="1.15516617405898E-06 -0.0180424468598241 -0.0215394748352687"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.239419768320061" />
|
|
<inertia
|
|
ixx="0.000285938919722783"
|
|
ixy="3.07101359163101E-09"
|
|
ixz="-2.21994118981953E-09"
|
|
iyy="0.000262727540304212"
|
|
iyz="4.4236583260078E-05"
|
|
izz="0.000119888082791859" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link4.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/link4.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="joint4"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0 -0.21 0"
|
|
rpy="1.5708 0 0" />
|
|
<parent
|
|
link="link_3" />
|
|
<child
|
|
link="link_4" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="-3.1"
|
|
upper="3.1"
|
|
effort="10"
|
|
velocity="3.92" /> <link name="root"/>
|
|
<joint name="root_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="root"/>
|
|
<child link="base_link"/>
|
|
</joint>
|
|
</joint>
|
|
<link
|
|
name="link_5">
|
|
<inertial>
|
|
<origin
|
|
xyz="3.19794786262152E-06 -0.0593808368101458 0.00736804250989326"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.218799761431678" />
|
|
<inertia
|
|
ixx="0.000350540363914072"
|
|
ixy="-3.41781619975602E-08"
|
|
ixz="-1.77056457224373E-08"
|
|
iyy="0.000104927867487581"
|
|
iyz="-7.82431228461971E-05"
|
|
izz="0.000334482418423629" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link5.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/link5.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="joint5"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="-1.5708 0 0" />
|
|
<parent
|
|
link="link_4" />
|
|
<child
|
|
link="link_5" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="-2.233"
|
|
upper="2.233"
|
|
effort="10"
|
|
velocity="3.92" />
|
|
</joint>
|
|
<link
|
|
name="link_6">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.000714234511756999 -0.000396718732824521 -0.0126723660946126"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.0649018034311231" />
|
|
<inertia
|
|
ixx="2.02766547502765E-05"
|
|
ixy="-1.32505200276849E-06"
|
|
ixz="-2.5845091522508E-08"
|
|
iyy="1.87986725225022E-05"
|
|
iyz="3.39471452125439E-09"
|
|
izz="3.17885459163081E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://ocs2_robotic_assets/resources/mobile_manipulator/realman/meshes/link6.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/link6.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint
|
|
name="joint6"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0 -0.144 0"
|
|
rpy="1.5708 0 0" />
|
|
<parent
|
|
link="link_5" />
|
|
<child
|
|
link="link_6" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<limit
|
|
lower="-6.28"
|
|
upper="6.28"
|
|
effort="10"
|
|
velocity="3.92" />
|
|
</joint>
|
|
</robot>
|