| <?xml version="1.0" encoding="utf-8"?>
|
| <robot
|
| name="arm"
|
| xmlns:xacro="http://ros.org/wiki/xacro">
|
|
|
| <link name="world"/>
|
| <joint name="fixed_base_joint" type="fixed">
|
| <parent link="world"/>
|
| <child link="base_link"/>
|
| </joint>
|
|
|
| <link
|
| name="base_link">
|
| <inertial>
|
| <origin
|
| xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="0.000226592553127906"
|
| ixy="-7.33974356968813E-08"
|
| ixz="2.13221970218123E-06"
|
| iyy="0.000269447877479622"
|
| iyz="8.15167478685076E-09"
|
| izz="0.000222318286704" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/base_link.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/base_link.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <link
|
| name="link1">
|
| <inertial>
|
| <origin
|
| xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="7.76684558296781E-05"
|
| ixy="1.09084650459916E-07"
|
| ixz="-1.97480532432411E-06"
|
| iyy="9.24967780161546E-05"
|
| iyz="9.91284646834672E-07"
|
| izz="8.24589062407806E-05" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link1.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link1.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint1"
|
| type="revolute">
|
| <origin
|
| xyz="0 0 0.123"
|
| rpy="0 0 -1.5708" />
|
| <parent
|
| link="base_link" />
|
| <child
|
| link="link1" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-2.618"
|
| upper="2.618"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
| <link
|
| name="link2">
|
| <inertial>
|
| <origin
|
| xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="0.000150112628108228"
|
| ixy="8.58974959950769E-05"
|
| ixz="-1.07428153464285E-06"
|
| iyy="0.00172585302855383"
|
| iyz="-9.93704792239686E-07"
|
| izz="0.00177445942914759" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link2.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link2.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint2"
|
| type="revolute">
|
| <origin
|
| xyz="0 0 0"
|
| rpy="1.5708 -0.10095 -1.5708" />
|
| <parent
|
| link="link1" />
|
| <child
|
| link="link2" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="0"
|
| upper="3.14"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
| <link
|
| name="link3">
|
| <inertial>
|
| <origin
|
| xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="0.000221686352136266"
|
| ixy="-7.57426543992343E-06"
|
| ixz="-6.3700062772173E-07"
|
| iyy="0.000100859162015934"
|
| iyz="-8.16202696860781E-07"
|
| izz="0.000241839316548946" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link3.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link3.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint3"
|
| type="revolute">
|
| <origin
|
| xyz="0.28503 0 0"
|
| rpy="0 0 1.3826" />
|
| <parent
|
| link="link2" />
|
| <child
|
| link="link3" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-2.967"
|
| upper="0"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
| <link
|
| name="link4">
|
| <inertial>
|
| <origin
|
| xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="3.82011730423098E-05"
|
| ixy="-4.92358351033589E-08"
|
| ixz="4.89589432983109E-08"
|
| iyy="4.87048555222491E-05"
|
| iyz="6.70802942486707E-08"
|
| izz="4.10592077565155E-05" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link4.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link4.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint4"
|
| type="revolute">
|
| <origin
|
| xyz="0.021984 0.25075 0"
|
| rpy="-1.5708 0 0" />
|
| <parent
|
| link="link3" />
|
| <child
|
| link="link4" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-1.832"
|
| upper="1.832"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
| <link
|
| name="link5">
|
| <inertial>
|
| <origin
|
| xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="4.39644269159173E-05"
|
| ixy="-3.59214840853815E-08"
|
| ixz="-1.89785003257649E-08"
|
| iyy="5.63173857792457E-05"
|
| iyz="-2.15407623722543E-07"
|
| izz="4.88713595021005E-05" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link5.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link5.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint5"
|
| type="revolute">
|
| <origin
|
| xyz="0 0 0"
|
| rpy="1.5708 -0.087266 0" />
|
| <parent
|
| link="link4" />
|
| <child
|
| link="link5" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-1.22"
|
| upper="1.22"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
| <link
|
| name="link6">
|
| <inertial>
|
| <origin
|
| xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="4.31750564711759E-05"
|
| ixy="-2.21295720427027E-08"
|
| ixz="-3.27825836857102E-12"
|
| iyy="9.99756357365307E-05"
|
| iyz="1.10337380549335E-07"
|
| izz="0.000118282295533688" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link6.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link6.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint6"
|
| type="revolute">
|
| <origin
|
| xyz="0 0.091 0.0014165"
|
| rpy="-1.5708 -1.5708 0" />
|
| <parent
|
| link="link5" />
|
| <child
|
| link="link6" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-3.14"
|
| upper="3.14"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
|
|
| <link
|
| name="link7">
|
| <inertial>
|
| <origin
|
| xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="9.99782519244544E-06"
|
| ixy="-1.57547595978589E-07"
|
| ixz="-2.71355785017816E-08"
|
| iyy="6.17952364356547E-06"
|
| iyz="-1.58939504838734E-06"
|
| izz="1.42102253390315E-05" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link7.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link7.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint7"
|
| type="prismatic">
|
| <origin
|
| xyz="0 0 0.13503"
|
| rpy="1.5708 0 1.5708" />
|
| <parent
|
| link="link6" />
|
| <child
|
| link="link7" />
|
| <axis
|
| xyz="0 0 -1" />
|
| <limit
|
| lower="0"
|
| upper="0.038"
|
| effort="100"
|
| velocity="1" />
|
| </joint>
|
|
|
| <link
|
| name="link8">
|
| <inertial>
|
| <origin
|
| xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
|
| rpy="0 0 0" />
|
| <mass
|
| value="0.00001" />
|
| <inertia
|
| ixx="9.99782474142963E-06"
|
| ixy="-1.57547666236405E-07"
|
| ixz="2.71355834243046E-08"
|
| iyy="6.17952362333486E-06"
|
| iyz="1.58939503259658E-06"
|
| izz="1.42102248648757E-05" />
|
| </inertial>
|
| <visual>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link8.STL" />
|
| </geometry>
|
| <material
|
| name="">
|
| <color
|
| rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
| </material>
|
| </visual>
|
| <collision>
|
| <origin
|
| xyz="0 0 0"
|
| rpy="0 0 0" />
|
| <geometry>
|
| <mesh
|
| filename="package://piper_description/meshes/link8.STL" />
|
| </geometry>
|
| </collision>
|
| </link>
|
| <joint
|
| name="joint8"
|
| type="prismatic">
|
| <origin
|
| xyz="0 0 0.13503"
|
| rpy="-1.5708 0 1.5708" />
|
| <parent
|
| link="link6" />
|
| <child
|
| link="link8" />
|
| <axis
|
| xyz="0 0 1" />
|
| <limit
|
| lower="-0.038"
|
| upper="0"
|
| effort="300"
|
| velocity="1" />
|
| </joint>
|
|
|
|
|
| <xacro:macro name="transmission_block" params="tran_name joint_name motor_name">
|
| <transmission name="${tran_name}">
|
| <type>transmission_interface/SimpleTransmission</type>
|
| <joint name="${joint_name}">
|
| <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
| </joint>
|
| <actuator name="$motor_name">
|
| <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
| <mechanicalReduction>1</mechanicalReduction>
|
| </actuator>
|
| </transmission>
|
| </xacro:macro>
|
|
|
| <xacro:transmission_block tran_name="tran1" joint_name="joint1" motor_name="motor1"/>
|
| <xacro:transmission_block tran_name="tran2" joint_name="joint2" motor_name="motor2"/>
|
| <xacro:transmission_block tran_name="tran3" joint_name="joint3" motor_name="motor3"/>
|
| <xacro:transmission_block tran_name="tran4" joint_name="joint4" motor_name="motor4"/>
|
| <xacro:transmission_block tran_name="tran5" joint_name="joint5" motor_name="motor5"/>
|
| <xacro:transmission_block tran_name="tran6" joint_name="joint6" motor_name="motor6"/>
|
| <xacro:transmission_block tran_name="tran7" joint_name="joint7" motor_name="motor7"/>
|
| <xacro:transmission_block tran_name="tran8" joint_name="joint8" motor_name="motor8"/>
|
|
|
| <gazebo>
|
| <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
| <robotNamespace>/piper_description</robotNamespace>
|
| <legacyModeNS>true</legacyModeNS>
|
| </plugin>
|
| </gazebo>
|
|
|
| <gazebo reference="base_link">
|
| <material>Gazebo/Black</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link1">
|
| <material>Gazebo/White</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link2">
|
| <material>Gazebo/White</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link3">
|
| <material>Gazebo/White</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link4">
|
| <material>Gazebo/Black</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link5">
|
| <material>Gazebo/White</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link6">
|
| <material>Gazebo/White</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link7">
|
| <material>Gazebo/Orange</material>
|
| </gazebo>
|
|
|
| <gazebo reference="link8">
|
| <material>Gazebo/Orange</material>
|
| </gazebo>
|
| </robot> |