| <?xml version="1.0" encoding="utf-8"?> |
| <robot |
| name="piper_description"> |
| <link |
| name="base_link"> |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| <visual> |
| <origin |
| xyz="0 0 0" |
| rpy="0 0 0" /> |
| <geometry> |
| <mesh |
| filename="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="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.0978679932242825" /> |
| <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="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="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="0" /> |
| </joint> |
| <link |
| name="link2"> |
| <inertial> |
| <origin |
| xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707" |
| rpy="0 0 0" /> |
| <mass |
| value="0.289571136953082" /> |
| <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="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="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.290583247455324" /> |
| <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="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="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.127087348341362" /> |
| <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="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="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.144711209371719" /> |
| <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="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="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.150196458571266" /> |
| <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="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="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.0264822500394006" /> |
| <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="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="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.038" |
| upper="0" |
| effort="100" |
| velocity="1" /> |
| </joint> |
|
|
| <link |
| name="link8"> |
| <inertial> |
| <origin |
| xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583" |
| rpy="0 0 0" /> |
| <mass |
| value="0.0264822490707451" /> |
| <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="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="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" |
| upper="0.038" |
| effort="100" |
| velocity="1" /> |
| </joint> |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| </robot> |