Create URDF for white xarm

This commit is contained in:
Ayzaan Wahid 2021-07-29 17:08:50 -04:00 committed by GitHub
parent 0e124cb2f1
commit 83fbd60d5b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -0,0 +1,317 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from xarm6_robot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="xarm6">
<!--
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.85 0.19 0.21 1.0"/>
</material>
<material name="Blue">
<color rgba="0.28 0.52 0.92 1.0"/>
</material>
<material name="Green">
<color rgba="0.23 0.72 0.32 1.0"/>
</material>
<material name="Yellow">
<color rgba="0.95 0.76 0.05 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_vhacd.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/collision/link6_vhacd.obj"/>
</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>
</robot>