512 lines
17 KiB
Text
512 lines
17 KiB
Text
<sdf version='1.9'>
|
|
<model name='rasmt'>
|
|
<joint name='to_world' type='fixed'>
|
|
<pose relative_to='__model__'>0 0 0 0 0 0</pose>
|
|
<parent>world</parent>
|
|
<child>rasmt_Base_Link</child>
|
|
</joint>
|
|
<link name='rasmt_Base_Link'>
|
|
<pose relative_to='to_world'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>-0.0030651 -3.2739e-05 0.082353 0 0 0</pose>
|
|
<mass>5.2929</mass>
|
|
<inertia>
|
|
<ixx>0.0076169</ixx>
|
|
<ixy>1.0121e-05</ixy>
|
|
<ixz>-0.00010622</ixz>
|
|
<iyy>0.0076597</iyy>
|
|
<iyz>6.511699999999999e-05</iyz>
|
|
<izz>0.01165</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Base_Link_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Base_Link.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Base_Link_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Base_Link.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
|
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Z_1' type='revolute'>
|
|
<pose relative_to='rasmt_Base_Link'>0 0 0.2533 3.141585307179587 0 0</pose>
|
|
<parent>rasmt_Base_Link</parent>
|
|
<child>rasmt_Fork_1</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-3.1416</lower>
|
|
<upper>3.1416</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Fork_1'>
|
|
<pose relative_to='rasmt_Rot_Z_1'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>0.043764 -0.0066984 -0.032285 0 0 0</pose>
|
|
<mass>0.67797</mass>
|
|
<inertia>
|
|
<ixx>0.0014091</ixx>
|
|
<ixy>-6.2674e-05</ixy>
|
|
<ixz>0.00057897</ixz>
|
|
<iyy>0.0017329</iyy>
|
|
<iyz>4.7826e-05</iyz>
|
|
<izz>0.0019056</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Fork_1_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Fork_1.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Fork_1_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Fork_1.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
|
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Y_1' type='revolute'>
|
|
<pose relative_to='rasmt_Fork_1'>0.1045 0 -0.0795 -3.141585307179587 0 0</pose>
|
|
<parent>rasmt_Fork_1</parent>
|
|
<child>rasmt_Link_1</child>
|
|
<axis>
|
|
<xyz>0 1 0</xyz>
|
|
<limit>
|
|
<lower>-1.5707</lower>
|
|
<upper>2.2863</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Link_1'>
|
|
<pose relative_to='rasmt_Rot_Y_1'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>-0.00042264 0 0.075171 0 0 0</pose>
|
|
<mass>1.8959</mass>
|
|
<inertia>
|
|
<ixx>0.0029317</ixx>
|
|
<ixy>-9.417e-06</ixy>
|
|
<ixz>5.5248e-05</ixz>
|
|
<iyy>0.0031666</iyy>
|
|
<iyz>-9.3067e-05</iyz>
|
|
<izz>0.0015477</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Link_1_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Link_1.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Link_1_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Link_1.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
|
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Z_2' type='revolute'>
|
|
<pose relative_to='rasmt_Link_1'>0 0 0.17502 0 0 0</pose>
|
|
<parent>rasmt_Link_1</parent>
|
|
<child>rasmt_Fork_2</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-3.1416</lower>
|
|
<upper>3.1416</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Fork_2'>
|
|
<pose relative_to='rasmt_Rot_Z_2'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>0.043764 0.0066984 0.032285 0 0 0</pose>
|
|
<mass>0.67797</mass>
|
|
<inertia>
|
|
<ixx>0.0014091</ixx>
|
|
<ixy>6.2674e-05</ixy>
|
|
<ixz>-0.00057897</ixz>
|
|
<iyy>0.0017329</iyy>
|
|
<iyz>4.7826e-05</iyz>
|
|
<izz>0.0019056</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Fork_2_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Fork_2.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Fork_2_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Fork_2.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
|
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Y_2' type='revolute'>
|
|
<pose relative_to='rasmt_Fork_2'>0.1045 0 0.0795 0 0 0</pose>
|
|
<parent>rasmt_Fork_2</parent>
|
|
<child>rasmt_Link_2</child>
|
|
<axis>
|
|
<xyz>0 1 0</xyz>
|
|
<limit>
|
|
<lower>-1.5707</lower>
|
|
<upper>2.2863</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Link_2'>
|
|
<pose relative_to='rasmt_Rot_Y_2'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>-0.00042264 0 0.075171 0 0 0</pose>
|
|
<mass>1.8959</mass>
|
|
<inertia>
|
|
<ixx>0.0029317</ixx>
|
|
<ixy>-9.4171e-06</ixy>
|
|
<ixz>5.5248e-05</ixz>
|
|
<iyy>0.0031666</iyy>
|
|
<iyz>-9.3067e-05</iyz>
|
|
<izz>0.0015477</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Link_2_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Link_2.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Link_2_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Link_2.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
|
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Z_3' type='revolute'>
|
|
<pose relative_to='rasmt_Link_2'>0 0 0.175 0 0 0</pose>
|
|
<parent>rasmt_Link_2</parent>
|
|
<child>rasmt_Fork_3</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-3.14159</lower>
|
|
<upper>3.14159</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Fork_3'>
|
|
<pose relative_to='rasmt_Rot_Z_3'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>0.0437644555284691 0.00669835350471771 0.0322846229336455 0 0 0</pose>
|
|
<mass>0.677972982551887</mass>
|
|
<inertia>
|
|
<ixx>0.00140908677953665</ixx>
|
|
<ixy>6.267434924451639e-05</ixy>
|
|
<ixz>-0.000578970009504215</ixz>
|
|
<iyy>0.00173285340301686</iyy>
|
|
<iyz>4.78263030621606e-05</iyz>
|
|
<izz>0.00190561919128035</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Fork_3_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Fork_3.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Fork_3_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Fork_3.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</diffuse>
|
|
<ambient>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Rot_Y_4' type='revolute'>
|
|
<pose relative_to='rasmt_Fork_3'>0.1045 0 0.0795 0 0 0</pose>
|
|
<parent>rasmt_Fork_3</parent>
|
|
<child>rasmt_Dock_Link</child>
|
|
<axis>
|
|
<xyz>0 1 0</xyz>
|
|
<limit>
|
|
<lower>-1.5707</lower>
|
|
<upper>2.2863</upper>
|
|
<effort>5.149</effort>
|
|
<velocity>0.99903</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Dock_Link'>
|
|
<pose relative_to='rasmt_Rot_Y_4'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>0.000487278098416338 0.0001516907797566372 0.08254557371325712 0 0 0</pose>
|
|
<mass>2.53391750781824</mass>
|
|
<inertia>
|
|
<ixx>0.006064508328644976</ixx>
|
|
<ixy>-2.015356731520154e-06</ixy>
|
|
<ixz>-7.294101423638933e-05</ixz>
|
|
<iyy>0.006094829365861896</iyy>
|
|
<iyz>-0.0001246350455024134</iyz>
|
|
<izz>0.002069011842474237</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Dock_Link_collision'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Dock_Link.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<collision name='rasmt_Dock_Link_fixed_joint_lump__rasmt_Grip_Body_collision_1'>
|
|
<pose>0 0 0.12324 -3.14159265358979 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Grip_Body.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Dock_Link_visual'>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Dock_Link.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</diffuse>
|
|
<ambient>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</ambient>
|
|
</material>
|
|
</visual>
|
|
<visual name='rasmt_Dock_Link_fixed_joint_lump__rasmt_Grip_Body_visual_1'>
|
|
<pose>0 0 0.12324 -3.14159265358979 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Grip_Body.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.6274499744176865 1 0.6274499744176865 1</diffuse>
|
|
<ambient>0.6274499744176865 1 0.6274499744176865 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Slide_1' type='prismatic'>
|
|
<pose relative_to='rasmt_Dock_Link'>0 -3.006528453019044e-16 0.21629 7.346410206709656e-06 -3.231089339497412e-15 1.5708</pose>
|
|
<parent>rasmt_Dock_Link</parent>
|
|
<child>rasmt_Grip_L</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<limit>
|
|
<lower>0</lower>
|
|
<upper>0.06</upper>
|
|
<effort>20</effort>
|
|
<velocity>0.2</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Grip_L'>
|
|
<pose relative_to='rasmt_Slide_1'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>-0.010118 0.010281 -0.0038252 0 0 0</pose>
|
|
<mass>0.021223</mass>
|
|
<inertia>
|
|
<ixx>6.5436e-06</ixx>
|
|
<ixy>-3.114e-06</ixy>
|
|
<ixz>2.8479e-06</ixz>
|
|
<iyy>1.9726e-05</iyy>
|
|
<iyz>1.6432e-06</iyz>
|
|
<izz>1.6355e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Grip_L_collision'>
|
|
<pose>-0.02 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Grip_L.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Grip_L_visual'>
|
|
<pose>-0.02 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Grip_L.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 1 1 1</diffuse>
|
|
<ambient>0.9411749988794327 1 1 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name='rasmt_Slide_2' type='prismatic'>
|
|
<pose relative_to='rasmt_Dock_Link'>0 -3.006528453019044e-16 0.21629 7.346410206709656e-06 3.231089339497412e-15 -1.5708</pose>
|
|
<parent>rasmt_Dock_Link</parent>
|
|
<child>rasmt_Grip_R</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<limit>
|
|
<lower>0</lower>
|
|
<upper>0.06</upper>
|
|
<effort>20</effort>
|
|
<velocity>0.2</velocity>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
</axis>
|
|
</joint>
|
|
<link name='rasmt_Grip_R'>
|
|
<pose relative_to='rasmt_Slide_2'>0 0 0 0 0 0</pose>
|
|
<inertial>
|
|
<pose>-0.010118 0.010281 -0.0038252 0 0 0</pose>
|
|
<mass>0.021223</mass>
|
|
<inertia>
|
|
<ixx>6.5436e-06</ixx>
|
|
<ixy>-3.114e-06</ixy>
|
|
<ixz>2.8479e-06</ixz>
|
|
<iyy>1.9726e-05</iyy>
|
|
<iyz>1.6432e-06</iyz>
|
|
<izz>1.6355e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='rasmt_Grip_R_collision'>
|
|
<pose>-0.02 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/collision/Grip_R.STL</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='rasmt_Grip_R_visual'>
|
|
<pose>-0.02 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://rasmt_support/meshes/visual/Grip_R.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0.9411749988794327 1 1 1</diffuse>
|
|
<ambient>0.9411749988794327 1 1 1</ambient>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<static>false</static>
|
|
<plugin name='ign_ros2_control' filename='libign_ros2_control-system.so'>
|
|
<parameters>/home/bill-finger/rasms_ws/install/share/rasmt_support/config/rasmt_effort_controllers.yaml</parameters>
|
|
</plugin>
|
|
</model>
|
|
</sdf>
|