80 lines
2.8 KiB
XML
80 lines
2.8 KiB
XML
<?xml version='1.0' encoding='utf-8'?>
|
|
<robot name="rotary_cartpole">
|
|
<link name="world" />
|
|
<link name="base_link">
|
|
<inertial>
|
|
<origin xyz="-0.00011 0.00117 0.06055" rpy="0 0 0" />
|
|
<mass value="0.921" />
|
|
<inertia ixx="0.002385" iyy="0.002484" izz="0.000559" ixy="0.0" iyz="-0.000149" ixz="6e-06" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="base_joint" type="fixed">
|
|
<parent link="world" />
|
|
<child link="base_link" />
|
|
</joint>
|
|
<link name="arm">
|
|
<inertial>
|
|
<origin xyz="0.014950488360794875 0.006089886527968399 0.004470745447817278" rpy="0 0 0" />
|
|
<mass value="0.012391951282440451" />
|
|
<inertia ixx="2.70e-06" iyy="7.80e-07" izz="2.44e-06" ixy="0.0" iyz="7.20e-08" ixz="0.0" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0.006947 -0.00395 -0.14796" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/arm_1.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0.006947 -0.00395 -0.14796" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/arm_1.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="motor_joint" type="revolute">
|
|
<origin xyz="-0.006947 0.00395 0.14796" rpy="0 0 0" />
|
|
<parent link="base_link" />
|
|
<child link="arm" />
|
|
<axis xyz="0 0 1" />
|
|
<limit lower="-1.5708" upper="1.5708" effort="10.0" velocity="200.0" />
|
|
<dynamics damping="0.001" />
|
|
</joint>
|
|
<link name="pendulum">
|
|
<inertial>
|
|
<origin xyz="0.06432778588634695 -0.05999895841669392 0.0008769789937631209" rpy="0 0 0" />
|
|
<mass value="0.035508993892747365" />
|
|
<inertia ixx="3.139576982078822e-05" iyy="9.431951659638859e-06" izz="4.07315891863556e-05" ixy="-1.8892943833253423e-06" iyz="0.0" ixz="0.0" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0.006895 -0.023224 -0.162953" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/pendulum_1.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0.006895 -0.023224 -0.162953" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="meshes/pendulum_1.stl" scale="0.001 0.001 0.001" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="pendulum_joint" type="continuous">
|
|
<origin xyz="0.000052 0.019274 0.014993" rpy="0 1.5708 0" />
|
|
<parent link="arm" />
|
|
<child link="pendulum" />
|
|
<axis xyz="0 -1 0" />
|
|
<dynamics damping="0.0001" />
|
|
</joint>
|
|
</robot> |