730 lines
25 KiB
Plaintext
730 lines
25 KiB
Plaintext
![]() |
<?xml version="1.0" ?>
|
||
|
<sdf version="1.5">
|
||
|
<model name="pr2_gripper">
|
||
|
<pose>-0.771000 0.188000 -0.790675 3.141593 -1.570796 3.141593</pose>
|
||
|
<link name="r_wrist_roll_link">
|
||
|
<pose>0.771000 -0.188000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.056408 0.000451 -0.001014 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.011352</ixx>
|
||
|
<ixy>-0.000016</ixy>
|
||
|
<ixz>-0.000001</ixz>
|
||
|
<iyy>0.011677</iyy>
|
||
|
<iyz>-0.000001</iyz>
|
||
|
<izz>0.011866</izz>
|
||
|
</inertia>
|
||
|
<mass>0.681070</mass>
|
||
|
</inertial>
|
||
|
<collision name="r_wrist_roll_link_geom">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/forearm_v0/wrist_roll_L.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>-1.000000</mu>
|
||
|
<mu2>-1.000000</mu2>
|
||
|
<fdir1>0.000000 0.000000 0.000000</fdir1>
|
||
|
<slip1>0.000000</slip1>
|
||
|
<slip2>0.000000</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
<bounce>
|
||
|
<restitution_coefficient>0.000000</restitution_coefficient>
|
||
|
<threshold>100000.000000</threshold>
|
||
|
</bounce>
|
||
|
<contact>
|
||
|
<ode>
|
||
|
<soft_cfm>0.000000</soft_cfm>
|
||
|
<soft_erp>0.200000</soft_erp>
|
||
|
<kp>1000000000000.000000</kp>
|
||
|
<kd>1.000000</kd>
|
||
|
<max_vel>0.000000</max_vel>
|
||
|
<min_depth>0.001000</min_depth>
|
||
|
</ode>
|
||
|
</contact>
|
||
|
</surface>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
</collision>
|
||
|
<visual name="r_wrist_roll_link_geom_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/forearm_v0/wrist_roll.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>__default__</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<visual name="r_wrist_roll_link_geom_r_gripper_palm_link_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/gripper_palm.dae</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_l_finger_link">
|
||
|
<pose>0.847910 -0.178000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000078</ixx>
|
||
|
<ixy>0.000001</ixy>
|
||
|
<ixz>-0.000010</ixz>
|
||
|
<iyy>0.000197</iyy>
|
||
|
<iyz>-0.000003</iyz>
|
||
|
<izz>0.000181</izz>
|
||
|
</inertia>
|
||
|
<mass>0.171260</mass>
|
||
|
</inertial>
|
||
|
<collision name="r_gripper_l_finger_link_geom">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>500.000000</mu>
|
||
|
<mu2>500.000000</mu2>
|
||
|
<fdir1>0.000000 0.000000 0.000000</fdir1>
|
||
|
<slip1>0.000000</slip1>
|
||
|
<slip2>0.000000</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
<bounce>
|
||
|
<restitution_coefficient>0.000000</restitution_coefficient>
|
||
|
<threshold>100000.000000</threshold>
|
||
|
</bounce>
|
||
|
<contact>
|
||
|
<ode>
|
||
|
<soft_cfm>0.000000</soft_cfm>
|
||
|
<soft_erp>0.200000</soft_erp>
|
||
|
<kp>1000000.000000</kp>
|
||
|
<kd>1.000000</kd>
|
||
|
<max_vel>0.000000</max_vel>
|
||
|
<min_depth>0.001000</min_depth>
|
||
|
</ode>
|
||
|
</contact>
|
||
|
</surface>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
</collision>
|
||
|
<visual name="r_gripper_l_finger_link_geom_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger.dae</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_l_finger_tip_link">
|
||
|
<pose>0.939280 -0.173050 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.004230 0.002840 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000008</ixx>
|
||
|
<ixy>0.000006</ixy>
|
||
|
<ixz>0.000000</ixz>
|
||
|
<iyy>0.000010</iyy>
|
||
|
<iyz>0.000000</iyz>
|
||
|
<izz>0.000015</izz>
|
||
|
</inertia>
|
||
|
<mass>0.044190</mass>
|
||
|
</inertial>
|
||
|
<collision name="r_gripper_l_finger_tip_link_geom">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger_tip.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>500.000000</mu>
|
||
|
<mu2>500.000000</mu2>
|
||
|
<fdir1>0.000000 0.000000 0.000000</fdir1>
|
||
|
<slip1>0.000000</slip1>
|
||
|
<slip2>0.000000</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
<bounce>
|
||
|
<restitution_coefficient>0.000000</restitution_coefficient>
|
||
|
<threshold>100000.000000</threshold>
|
||
|
</bounce>
|
||
|
<contact>
|
||
|
<ode>
|
||
|
<soft_cfm>0.000000</soft_cfm>
|
||
|
<soft_erp>0.200000</soft_erp>
|
||
|
<kp>10000000.000000</kp>
|
||
|
<kd>1.000000</kd>
|
||
|
<max_vel>0.000000</max_vel>
|
||
|
<min_depth>0.001000</min_depth>
|
||
|
</ode>
|
||
|
</contact>
|
||
|
</surface>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
</collision>
|
||
|
<visual name="r_gripper_l_finger_tip_link_geom_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger_tip.dae</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<sensor name="r_gripper_l_finger_tip_contact_sensor" type="contact">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<contact>
|
||
|
<collision>r_gripper_l_finger_tip_link_geom</collision>
|
||
|
<topic>__default_topic__</topic>
|
||
|
</contact>
|
||
|
<always_on>0</always_on>
|
||
|
<update_rate>100.000000</update_rate>
|
||
|
<visualize>0</visualize>
|
||
|
</sensor>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_motor_slider_link">
|
||
|
<pose>0.939280 -0.188000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.001000</ixx>
|
||
|
<ixy>0.000000</ixy>
|
||
|
<ixz>0.000000</ixz>
|
||
|
<iyy>0.001000</iyy>
|
||
|
<iyz>0.000000</iyz>
|
||
|
<izz>0.001000</izz>
|
||
|
</inertia>
|
||
|
<mass>0.010000</mass>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_motor_screw_link">
|
||
|
<pose>0.939280 -0.188000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000100</ixx>
|
||
|
<ixy>0.000000</ixy>
|
||
|
<ixz>0.000000</ixz>
|
||
|
<iyy>0.000100</iyy>
|
||
|
<iyz>0.000000</iyz>
|
||
|
<izz>0.000100</izz>
|
||
|
</inertia>
|
||
|
<mass>0.010000</mass>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_r_finger_link">
|
||
|
<pose>0.847910 -0.198000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000077</ixx>
|
||
|
<ixy>-0.000002</ixy>
|
||
|
<ixz>-0.000008</ixz>
|
||
|
<iyy>0.000198</iyy>
|
||
|
<iyz>0.000002</iyz>
|
||
|
<izz>0.000181</izz>
|
||
|
</inertia>
|
||
|
<mass>0.173890</mass>
|
||
|
</inertial>
|
||
|
<collision name="r_gripper_r_finger_link_geom">
|
||
|
<pose>0.000000 0.000000 0.000000 -3.141590 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>500.000000</mu>
|
||
|
<mu2>500.000000</mu2>
|
||
|
<fdir1>0.000000 0.000000 0.000000</fdir1>
|
||
|
<slip1>0.000000</slip1>
|
||
|
<slip2>0.000000</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
<bounce>
|
||
|
<restitution_coefficient>0.000000</restitution_coefficient>
|
||
|
<threshold>100000.000000</threshold>
|
||
|
</bounce>
|
||
|
<contact>
|
||
|
<ode>
|
||
|
<soft_cfm>0.000000</soft_cfm>
|
||
|
<soft_erp>0.200000</soft_erp>
|
||
|
<kp>1000000.000000</kp>
|
||
|
<kd>1.000000</kd>
|
||
|
<max_vel>0.000000</max_vel>
|
||
|
<min_depth>0.001000</min_depth>
|
||
|
</ode>
|
||
|
</contact>
|
||
|
</surface>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
</collision>
|
||
|
<visual name="r_gripper_r_finger_link_geom_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger.dae</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_r_finger_tip_link">
|
||
|
<pose>0.939280 -0.202950 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.004230 -0.002840 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000008</ixx>
|
||
|
<ixy>-0.000006</ixy>
|
||
|
<ixz>0.000000</ixz>
|
||
|
<iyy>0.000010</iyy>
|
||
|
<iyz>0.000000</iyz>
|
||
|
<izz>0.000015</izz>
|
||
|
</inertia>
|
||
|
<mass>0.044190</mass>
|
||
|
</inertial>
|
||
|
<collision name="r_gripper_r_finger_tip_link_geom">
|
||
|
<pose>0.000000 0.000000 0.000000 -3.141590 -0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger_tip.stl</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>500.000000</mu>
|
||
|
<mu2>500.000000</mu2>
|
||
|
<fdir1>0.000000 0.000000 0.000000</fdir1>
|
||
|
<slip1>0.000000</slip1>
|
||
|
<slip2>0.000000</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
<bounce>
|
||
|
<restitution_coefficient>0.000000</restitution_coefficient>
|
||
|
<threshold>100000.000000</threshold>
|
||
|
</bounce>
|
||
|
<contact>
|
||
|
<ode>
|
||
|
<soft_cfm>0.000000</soft_cfm>
|
||
|
<soft_erp>0.200000</soft_erp>
|
||
|
<kp>10000000.000000</kp>
|
||
|
<kd>1.000000</kd>
|
||
|
<max_vel>0.000000</max_vel>
|
||
|
<min_depth>0.001000</min_depth>
|
||
|
</ode>
|
||
|
</contact>
|
||
|
</surface>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
</collision>
|
||
|
<visual name="r_gripper_r_finger_tip_link_geom_visual">
|
||
|
<pose>0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://pr2/meshes/gripper_v0/l_finger_tip.dae</uri>
|
||
|
<scale>1.000000 1.000000 1.000000</scale>
|
||
|
<uri>__default__</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
<laser_retro>0.000000</laser_retro>
|
||
|
<transparency>0.000000</transparency>
|
||
|
</visual>
|
||
|
<sensor name="r_gripper_r_finger_tip_contact_sensor" type="contact">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<contact>
|
||
|
<collision>r_gripper_r_finger_tip_link_geom</collision>
|
||
|
<topic>__default_topic__</topic>
|
||
|
</contact>
|
||
|
<always_on>0</always_on>
|
||
|
<update_rate>100.000000</update_rate>
|
||
|
<visualize>0</visualize>
|
||
|
</sensor>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="torso_lift_motor_screw_link">
|
||
|
<pose>-0.150000 0.000000 0.751000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.001000</ixx>
|
||
|
<ixy>0.000000</ixy>
|
||
|
<ixz>0.000000</ixz>
|
||
|
<iyy>0.001000</iyy>
|
||
|
<iyz>0.000000</iyz>
|
||
|
<izz>0.001000</izz>
|
||
|
</inertia>
|
||
|
<mass>1.000000</mass>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_l_parallel_link">
|
||
|
<pose>0.829910 -0.157000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000078</ixx>
|
||
|
<ixy>0.000001</ixy>
|
||
|
<ixz>-0.000010</ixz>
|
||
|
<iyy>0.000197</iyy>
|
||
|
<iyz>-0.000003</iyz>
|
||
|
<izz>0.000181</izz>
|
||
|
</inertia>
|
||
|
<mass>0.171260</mass>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<link name="r_gripper_r_parallel_link">
|
||
|
<pose>0.829910 -0.219000 0.790675 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertial>
|
||
|
<pose>0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.000077</ixx>
|
||
|
<ixy>-0.000002</ixy>
|
||
|
<ixz>-0.000008</ixz>
|
||
|
<iyy>0.000198</iyy>
|
||
|
<iyz>0.000002</iyz>
|
||
|
<izz>0.000181</izz>
|
||
|
</inertia>
|
||
|
<mass>0.173890</mass>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<velocity_decay />
|
||
|
</link>
|
||
|
<joint name="r_gripper_l_finger_joint" type="revolute">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_wrist_roll_link</parent>
|
||
|
<child>r_gripper_l_finger_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.020000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>0.000000</lower>
|
||
|
<upper>0.548000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_l_finger_tip_joint" type="revolute">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_l_finger_link</parent>
|
||
|
<child>r_gripper_l_finger_tip_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.001000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>0.000000</lower>
|
||
|
<upper>0.548000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 -1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_motor_slider_joint" type="prismatic">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_wrist_roll_link</parent>
|
||
|
<child>r_gripper_motor_slider_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-0.100000</lower>
|
||
|
<upper>0.100000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>1.000000 0.000000 0.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_motor_screw_joint" type="revolute">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_motor_slider_link</parent>
|
||
|
<child>r_gripper_motor_screw_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000100</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 1.000000 0.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_r_finger_joint" type="revolute">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_wrist_roll_link</parent>
|
||
|
<child>r_gripper_r_finger_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.020000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>0.000000</lower>
|
||
|
<upper>0.548000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 -1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_r_finger_tip_joint" type="revolute">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_r_finger_link</parent>
|
||
|
<child>r_gripper_r_finger_tip_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.001000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>0.000000</lower>
|
||
|
<upper>0.548000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_r_screw_screw_joint" type="screw">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_r_finger_tip_link</parent>
|
||
|
<child>r_gripper_motor_screw_link</child>
|
||
|
<thread_pitch>-3141.600000</thread_pitch>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 1.000000 0.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_l_screw_screw_joint" type="screw">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_l_finger_tip_link</parent>
|
||
|
<child>r_gripper_motor_screw_link</child>
|
||
|
<thread_pitch>3141.600000</thread_pitch>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 1.000000 0.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_r_parallel_root_joint" type="revolute">
|
||
|
<pose>0.058910 -0.031000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_r_parallel_link</parent>
|
||
|
<child>r_wrist_roll_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.200000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 -1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_l_parallel_root_joint" type="revolute">
|
||
|
<pose>0.058910 0.031000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_l_parallel_link</parent>
|
||
|
<child>r_wrist_roll_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.200000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_r_parallel_tip_joint" type="revolute">
|
||
|
<pose>-0.018000 -0.021000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_r_parallel_link</parent>
|
||
|
<child>r_gripper_r_finger_tip_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_l_parallel_tip_joint" type="revolute">
|
||
|
<pose>-0.018000 0.021000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_l_parallel_link</parent>
|
||
|
<child>r_gripper_l_finger_tip_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 0.000000 1.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name="r_gripper_joint" type="prismatic">
|
||
|
<pose>0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
|
||
|
<parent>r_gripper_r_finger_tip_link</parent>
|
||
|
<child>r_gripper_l_finger_tip_link</child>
|
||
|
<axis>
|
||
|
<dynamics>
|
||
|
<damping>0.000000</damping>
|
||
|
<friction>0.000000</friction>
|
||
|
</dynamics>
|
||
|
<limit>
|
||
|
<lower>-10000000000000000.000000</lower>
|
||
|
<upper>10000000000000000.000000</upper>
|
||
|
<effort>0.000000</effort>
|
||
|
<velocity>0.000000</velocity>
|
||
|
</limit>
|
||
|
<xyz>0.000000 1.000000 0.000000</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<static>0</static>
|
||
|
</model>
|
||
|
</sdf>
|