add XArm6 URDF with optimized collision meshes and example (XArm gripper needs more work) python3 -m pybullet_envs.examples.xarm
555 lines
19 KiB
XML
555 lines
19 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from xarm6_with_gripper.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="xarm6_with_gripper">
|
|
<!-- <xacro:load_gripper attach_to="$(arg prefix)link6" /> -->
|
|
<!--
|
|
Author: Jason Peng <jason@ufactory.cc>
|
|
Contributers:
|
|
-->
|
|
<gazebo>
|
|
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
|
<robotNamespace>/xarm</robotNamespace>
|
|
<!-- <controlPeriod>0.0001</controlPeriod> -->
|
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
|
<legacyModeNS>true</legacyModeNS>
|
|
<!-- <preserveWorldVelocity>true</preserveWorldVelocity> -->
|
|
</plugin>
|
|
</gazebo>
|
|
<link name="world"/>
|
|
<joint name="world_joint" type="fixed">
|
|
<parent link="world"/>
|
|
<child link="link_base"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</joint>
|
|
<material name="Black">
|
|
<color rgba="0.0 0.0 0.0 1.0"/>
|
|
</material>
|
|
<material name="Red">
|
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
|
</material>
|
|
<material name="White">
|
|
<color rgba="1.0 1.0 1.0 1.0"/>
|
|
</material>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
<link name="link_base">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/base.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/base_vhacd.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.09103"/>
|
|
<mass value="2.7"/>
|
|
<inertia ixx="0.00494875" ixy="-3.5E-06" ixz="1.25E-05" iyy="0.00494174" iyz="1.67E-06" izz="0.002219"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link1">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link1.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/link1_vhacd.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.002 0.02692 -0.01332"/>
|
|
<mass value="2.16"/>
|
|
<inertia ixx="0.00539427" ixy="1.095E-05" ixz="1.635E-06" iyy="0.0048979" iyz="0.000793" izz="0.00311573"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint1" type="revolute">
|
|
<parent link="link_base"/>
|
|
<child link="link1"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0.267"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="50.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<link name="link2">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link2.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/link2_vhacd2.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.03531 -0.21398 0.03386"/>
|
|
<mass value="1.71"/>
|
|
<inertia ixx="0.0248674" ixy="-0.00430651" ixz="-0.00067797" iyy="0.00485548" iyz="0.00457245" izz="0.02387827"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint2" type="revolute">
|
|
<parent link="link1"/>
|
|
<child link="link2"/>
|
|
<origin rpy="-1.5708 0 0" xyz="0 0 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="50.0" lower="-2.059" upper="2.0944" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<link name="link3">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link3.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/link3_vhacd.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.06781 0.10749 0.01457"/>
|
|
<mass value="1.384"/>
|
|
<inertia ixx="0.0053694" ixy="0.0014185" ixz="-0.00092094" iyy="0.0032423" iyz="-0.00169178" izz="0.00501731"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint3" type="revolute">
|
|
<parent link="link2"/>
|
|
<child link="link3"/>
|
|
<origin rpy="0 0 0" xyz="0.0535 -0.2845 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="32.0" lower="-3.927" upper="0.19198" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<link name="link4">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link4.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/link4_vhacd.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.00021 0.02578 -0.02538"/>
|
|
<mass value="1.115"/>
|
|
<inertia ixx="0.00439263" ixy="5.028E-05" ixz="1.374E-05" iyy="0.0040077" iyz="0.00045338" izz="0.00110321"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint4" type="revolute">
|
|
<parent link="link3"/>
|
|
<child link="link4"/>
|
|
<origin rpy="-1.5708 0 0" xyz="0.0775 0.3425 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="32.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<link name="link5">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link5.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="White"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/collision/link5_vhacd.obj"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.05428 0.01781 0.00543"/>
|
|
<mass value="1.275"/>
|
|
<inertia ixx="0.001202758" ixy="0.000492428" ixz="-0.00039147" iyy="0.0022876" iyz="-1.235E-04" izz="0.0026866"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint5" type="revolute">
|
|
<parent link="link4"/>
|
|
<child link="link5"/>
|
|
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="32.0" lower="-1.69297" upper="3.14159265359" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<link name="link6">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link6.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="Silver"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="package://xarm_description/meshes/xarm6/visual/link6.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0.00064 -0.00952"/>
|
|
<mass value="0.1096"/>
|
|
<inertia ixx="4.5293E-05" ixy="0" ixz="0" iyy="4.8111E-05" iyz="0" izz="7.9715E-05"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="joint6" type="revolute">
|
|
<parent link="link5"/>
|
|
<child link="link6"/>
|
|
<origin rpy="-1.5708 0 0" xyz="0.076 0.097 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="20.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
|
<dynamics damping="1.0" friction="1.0"/>
|
|
</joint>
|
|
<transmission name="tran1">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint1">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor1">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>100</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="tran2">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint2">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor2">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>reduction</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="tran3">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint3">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor3">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>reduction</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="tran4">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint4">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor3">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>reduction</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="tran5">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint5">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor5">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>reduction</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="tran6">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="joint6">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="motor6">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>reduction</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<gazebo reference="link_base">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link1">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link2">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link3">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link4">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link5">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="link6">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<!-- gazebo plugin -->
|
|
<!-- <xacro:gazebo_ros_control_plugin namespace="${ns}"/> -->
|
|
<joint name="gripper_fix" type="fixed">
|
|
<parent link="link6"/>
|
|
<child link="xarm_gripper_base_link"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</joint>
|
|
<link name="xarm_gripper_base_link">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.00065489 -0.0018497 0.048028"/>
|
|
<mass value="0.54156"/>
|
|
<inertia ixx="0.00047106" ixy="3.9292E-07" ixz="2.6537E-06" iyy="0.00033072" iyz="-1.0975E-05" izz="0.00025642"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/base_link.STL"/>
|
|
</geometry>
|
|
<!-- <material
|
|
name="">
|
|
<color
|
|
rgba="0.89804 0.91765 0.92941 1" />
|
|
</material> -->
|
|
<material name="White">
|
|
<color rgba="1.0 1.0 1.0 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/base_link.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="left_outer_knuckle">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="2.9948E-14 0.021559 0.015181"/>
|
|
<mass value="0.033618"/>
|
|
<inertia ixx="1.9111E-05" ixy="-1.8803E-17" ixz="-1.1002E-17" iyy="6.6256E-06" iyz="-7.3008E-06" izz="1.3185E-05"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_outer_knuckle.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_outer_knuckle.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="drive_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0.035 0.059098"/>
|
|
<parent link="xarm_gripper_base_link"/>
|
|
<child link="left_outer_knuckle"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
</joint>
|
|
<link name="left_finger">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-2.4536E-14 -0.016413 0.029258"/>
|
|
<mass value="0.048304"/>
|
|
<inertia ixx="1.7493E-05" ixy="-4.2156E-19" ixz="6.9164E-18" iyy="1.7225E-05" iyz="4.6433E-06" izz="5.1466E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_finger.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_finger.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="left_finger_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0.035465 0.042039"/>
|
|
<parent link="left_outer_knuckle"/>
|
|
<child link="left_finger"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
<mimic joint="drive_joint" multiplier="1" offset="0"/>
|
|
</joint>
|
|
<link name="left_inner_knuckle">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="1.86600784687907E-06 0.0220467847633621 0.0261334672830885"/>
|
|
<mass value="0.0230125781256706"/>
|
|
<inertia ixx="6.09490024271906E-06" ixy="6.06651326160071E-11" ixz="7.19102670500635E-11" iyy="6.01955084375188E-06" iyz="-2.75316812991721E-06" izz="5.07862004479903E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_inner_knuckle.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/left_inner_knuckle.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="left_inner_knuckle_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0.02 0.074098"/>
|
|
<parent link="xarm_gripper_base_link"/>
|
|
<child link="left_inner_knuckle"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
<mimic joint="drive_joint" multiplier="1" offset="0"/>
|
|
</joint>
|
|
<link name="right_outer_knuckle">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-3.1669E-14 -0.021559 0.015181"/>
|
|
<mass value="0.033618"/>
|
|
<inertia ixx="1.9111E-05" ixy="-1.8789E-17" ixz="1.0986E-17" iyy="6.6256E-06" iyz="7.3008E-06" izz="1.3185E-05"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_outer_knuckle.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_outer_knuckle.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="right_outer_knuckle_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 -0.035 0.059098"/>
|
|
<parent link="xarm_gripper_base_link"/>
|
|
<child link="right_outer_knuckle"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
<mimic joint="drive_joint" multiplier="1" offset="0"/>
|
|
</joint>
|
|
<link name="right_finger">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="2.5618E-14 0.016413 0.029258"/>
|
|
<mass value="0.048304"/>
|
|
<inertia ixx="1.7493E-05" ixy="-5.0014E-19" ixz="-7.5079E-18" iyy="1.7225E-05" iyz="-4.6435E-06" izz="5.1466E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_finger.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_finger.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="right_finger_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 -0.035465 0.042039"/>
|
|
<parent link="right_outer_knuckle"/>
|
|
<child link="right_finger"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
<mimic joint="drive_joint" multiplier="1" offset="0"/>
|
|
</joint>
|
|
<link name="right_inner_knuckle">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="1.866E-06 -0.022047 0.026133"/>
|
|
<mass value="0.023013"/>
|
|
<inertia ixx="6.0949E-06" ixy="-6.0665E-11" ixz="7.191E-11" iyy="6.0197E-06" iyz="2.7531E-06" izz="5.0784E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_inner_knuckle.STL"/>
|
|
</geometry>
|
|
<material name="Silver">
|
|
<color rgba="0.753 0.753 0.753 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://xarm_gripper/meshes/right_inner_knuckle.STL"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="right_inner_knuckle_joint" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 -0.02 0.074098"/>
|
|
<parent link="xarm_gripper_base_link"/>
|
|
<child link="right_inner_knuckle"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="50" lower="0" upper="0.85" velocity="2"/>
|
|
<mimic joint="drive_joint" multiplier="1" offset="0"/>
|
|
</joint>
|
|
<transmission name="drive_joint_trans">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="drive_joint">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="drive_joint_motor">
|
|
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<gazebo reference="xarm_gripper_base_link">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="left_outer_knuckle">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="left_finger">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="left_inner_knuckle">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="right_outer_knuckle">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="right_finger">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
<gazebo reference="right_inner_knuckle">
|
|
<selfCollide>true</selfCollide>
|
|
</gazebo>
|
|
</robot>
|
|
|