444 lines
17 KiB
XML
444 lines
17 KiB
XML
<?xml version="1.0" ?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from openarm_grip.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="openarm_grip">
|
|
<material name="silver">
|
|
<color rgba="0.700 0.700 0.700 1.000"/>
|
|
</material>
|
|
<transmission name="rev1_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev1">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev1_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev2_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev2">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev2_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev3_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev3">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev3_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev4_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev4">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev4_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev5_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev5">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev5_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev6_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev6">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev6_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="rev7_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="rev7">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="rev7_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="slider_left_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="slider_left">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="slider_left_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="slider_right_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="slider_right">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="slider_right_actr">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<gazebo>
|
|
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin"/>
|
|
</gazebo>
|
|
<gazebo reference="base_link">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
<gravity>true</gravity>
|
|
</gazebo>
|
|
<gazebo reference="J2_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="J3_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="J4_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="J5_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="J6_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="J7_v1_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="grip_attach_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="left_jaw_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<gazebo reference="right_jaw_1">
|
|
<material>Gazebo/Silver</material>
|
|
<mu1>0.2</mu1>
|
|
<mu2>0.2</mu2>
|
|
<self_collide>true</self_collide>
|
|
</gazebo>
|
|
<link name="world"/>
|
|
<joint name="world_joint" type="fixed">
|
|
<parent link="world"/>
|
|
<child link="base_link"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
|
|
</joint>
|
|
<link name="base_link">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="1.659663993709495e-08 0.00015470291788827239 -0.03159176823669262"/>
|
|
<mass value="0.9159780860248254"/>
|
|
<inertia ixx="0.000802" ixy="-0.0" ixz="0.0" iyy="0.000799" iyz="-0.0" izz="0.001037"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J2_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.002300730781673588 -0.00021691236314287158 0.02760602616888808"/>
|
|
<mass value="0.49220952328993495"/>
|
|
<inertia ixx="0.000316" ixy="0.0" ixz="-2.2e-05" iyy="0.000717" iyz="-3e-06" izz="0.00059"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="-0.0 -0.0 0.00225"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="-0.0 -0.0 0.00225"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J3_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.029725947365562236 0.014084733811091961 0.002458883521108013"/>
|
|
<mass value="0.6372830939810512"/>
|
|
<inertia ixx="0.000647" ixy="4e-06" ixz="2e-06" iyy="0.000437" iyz="-5.2e-05" izz="0.00075"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="-0.02975 0.0 -0.0425"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="-0.02975 0.0 -0.0425"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J4_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="8.405076184644401e-05 0.1358717615053826 0.018429965102241944"/>
|
|
<mass value="1.1025467379280594"/>
|
|
<inertia ixx="0.011905" ixy="-1e-06" ixz="-4e-06" iyy="0.00114" iyz="-0.001657" izz="0.011791"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.06041 -0.052607"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.06041 -0.052607"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J5_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.028086778609557873 -0.06237848032279486 0.015103464347573828"/>
|
|
<mass value="0.7296865736952145"/>
|
|
<inertia ixx="0.002473" ixy="-7e-05" ixz="1.8e-05" iyy="0.000853" iyz="0.00038" izz="0.002847"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="-0.029755 -0.298846 -0.0925"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="-0.029755 -0.298846 -0.0925"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J6_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.016428123043712856 -0.04271549352047854 0.009023923091251038"/>
|
|
<mass value="1.0339114396114095"/>
|
|
<inertia ixx="0.000881" ixy="0.000136" ixz="-1.1e-05" iyy="0.000614" iyz="0.000102" izz="0.001054"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.167496 -0.118765"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.167496 -0.118765"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="J7_v1_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.03510690863628159 0.0004066264284608781 0.001093657345024951"/>
|
|
<mass value="0.33288025570396623"/>
|
|
<inertia ixx="0.00014" ixy="-0.0" ixz="2e-06" iyy="0.000179" iyz="7e-06" izz="0.000207"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="-0.0355 -0.048796 -0.1425"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="-0.0355 -0.048796 -0.1425"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="grip_attach_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-3.544262443517109e-05 -0.08091067772872827 0.004061313352520662"/>
|
|
<mass value="0.8188472642682024"/>
|
|
<inertia ixx="0.001113" ixy="1e-06" ixz="2e-06" iyy="0.00061" iyz="-2.2e-05" izz="0.001556"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.051826 -0.15765"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.051826 -0.15765"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="left_jaw_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.01737096632831872 -0.017398412728963003 0.004062150876211923"/>
|
|
<mass value="0.2869555939898112"/>
|
|
<inertia ixx="0.000209" ixy="1.6e-05" ixz="-4e-06" iyy="9.7e-05" iyz="3e-06" izz="0.000185"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0775 0.069829 -0.169736"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0775 0.069829 -0.169736"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="right_jaw_1">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.0173972747583793 -0.018685385724924758 -0.0017497641003002828"/>
|
|
<mass value="0.285094009790996"/>
|
|
<inertia ixx="0.000211" ixy="-1.6e-05" ixz="4e-06" iyy="0.000115" iyz="3.9e-05" izz="0.000169"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="-0.0775 0.069829 -0.169736"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<material name="silver"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="-0.0775 0.069829 -0.169736"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="rev1" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.00225"/>
|
|
<parent link="base_link"/>
|
|
<child link="J2_v1_1"/>
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-2.356194" upper="2.356194" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev2" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.02975 -0.0 0.04475"/>
|
|
<parent link="J2_v1_1"/>
|
|
<child link="J3_v1_1"/>
|
|
<axis xyz="-1.0 -0.0 0.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-3.054326" upper="0.0" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev3" type="revolute">
|
|
<origin rpy="0 0 0" xyz="-0.02975 0.06041 0.010107"/>
|
|
<parent link="J3_v1_1"/>
|
|
<child link="J4_v1_1"/>
|
|
<axis xyz="-0.0 0.986291 0.165017"/>
|
|
<limit acceleration="0.5" effort="100" lower="-2.094395" upper="2.094395" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev4" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.029755 0.238436 0.039893"/>
|
|
<parent link="J4_v1_1"/>
|
|
<child link="J5_v1_1"/>
|
|
<axis xyz="1.0 0.0 0.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-3.141593" upper="0.0" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev5" type="revolute">
|
|
<origin rpy="0 0 0" xyz="-0.029755 -0.13135 0.026265"/>
|
|
<parent link="J5_v1_1"/>
|
|
<child link="J6_v1_1"/>
|
|
<axis xyz="0.0 -0.980588 0.196078"/>
|
|
<limit acceleration="0.5" effort="100" lower="-2.094395" upper="2.094395" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev6" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.0355 -0.1187 0.023735"/>
|
|
<parent link="J6_v1_1"/>
|
|
<child link="J7_v1_1"/>
|
|
<axis xyz="-1.0 0.0 -0.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-1.570796" upper="1.570796" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="rev7" type="revolute">
|
|
<origin rpy="0 0 0" xyz="-0.0355 0.00303 0.01515"/>
|
|
<parent link="J7_v1_1"/>
|
|
<child link="grip_attach_1"/>
|
|
<axis xyz="0.0 0.196078 0.980588"/>
|
|
<limit acceleration="0.5" effort="100" lower="-1.5" upper="1.5" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="slider_left" type="prismatic">
|
|
<origin rpy="0 0 0" xyz="-0.0775 -0.121655 0.012086"/>
|
|
<parent link="grip_attach_1"/>
|
|
<child link="left_jaw_1"/>
|
|
<axis xyz="-1.0 0.0 -0.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<joint name="slider_right" type="prismatic">
|
|
<origin rpy="0 0 0" xyz="0.0775 -0.121655 0.012086"/>
|
|
<parent link="grip_attach_1"/>
|
|
<child link="right_jaw_1"/>
|
|
<axis xyz="1.0 -0.0 0.0"/>
|
|
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
<mimic joint="slider_left"/>
|
|
</joint>
|
|
</robot>
|