<?xml version="1.0" encoding="utf-8"?> <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) Commit Version: 1.6.0-1-g15f4949 Build Version: 1.6.7594.29634 For more information, please see http://wiki.ros.org/sw_urdf_exporter --> <robot name="SO_5DOF_ARM100_8j_URDF.SLDASM"> <link name="Base"> <inertial> <origin xyz="-2.45960666746703E-07 0.0311418169687909 0.0175746661003382" rpy="0 0 0" /> <mass value="0.193184127927598" /> <inertia ixx="0.000137030709467877" ixy="2.10136126944992E-08" ixz="4.24087422551286E-09" iyy="0.000169089551209259" iyz="2.26514711036514E-05" izz="0.000145097720857224" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Base.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.STL" /> </geometry> </collision> </link> <link name="Rotation_Pitch"> <inertial> <origin xyz="-9.07886224712597E-05 0.0590971820568318 0.031089016892169" rpy="0 0 0" /> <mass value="0.119226314127197" /> <inertia ixx="5.90408775624429E-05" ixy="4.90800532852998E-07" ixz="-5.90451772654387E-08" iyy="3.21498601038881E-05" iyz="-4.58026206663885E-06" izz="5.86058514263952E-05" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Rotation_Pitch.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="Rotation_Pitch.STL" /> </geometry> </collision> </link> <joint name="Rotation" type="continuous"> <origin xyz="0 -0.0452 0.0165" rpy="1.5708 0 0" /> <parent link="Base" /> <child link="Rotation_Pitch" /> <axis xyz="0 1 0" /> </joint> <link name="Upper_Arm"> <inertial> <origin xyz="-1.7205170190925E-05 0.0701802156327694 0.00310545118155671" rpy="0 0 0" /> <mass value="0.162409284599177" /> <inertia ixx="0.000167153146617081" ixy="1.03902689187701E-06" ixz="-1.20161820645189E-08" iyy="7.01946992214245E-05" iyz="2.11884806298698E-06" izz="0.000213280241160769" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Upper_Arm.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="Upper_Arm.STL" /> </geometry> </collision> </link> <joint name="Pitch" type="continuous"> <origin xyz="0 0.1025 0.0306" rpy="0 0 0" /> <parent link="Rotation_Pitch" /> <child link="Upper_Arm" /> <axis xyz="1 0 0" /> </joint> <link name="Lower_Arm"> <inertial> <origin xyz="-0.00339603710186651 0.00137796353960074 0.0768006751156044" rpy="0 0 0" /> <mass value="0.147967774582291" /> <inertia ixx="0.000105333995841409" ixy="1.73059237226499E-07" ixz="-1.1720305455211E-05" iyy="0.000138766654485212" iyz="1.77429964684103E-06" izz="5.08741652515214E-05" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Lower_Arm.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="Lower_Arm.STL" /> </geometry> </collision> </link> <joint name="Elbow" type="continuous"> <origin xyz="0 0.11257 0.028" rpy="0 0 0" /> <parent link="Upper_Arm" /> <child link="Lower_Arm" /> <axis xyz="1 0 0" /> </joint> <link name="Wrist_Pitch_Roll"> <inertial> <origin xyz="-0.00852653127372418 -0.0352278997897927 -2.34622481569413E-05" rpy="0 0 0" /> <mass value="0.066132067097723" /> <inertia ixx="1.95717492443445E-05" ixy="-6.62714374412293E-07" ixz="5.20089016442066E-09" iyy="2.38028417569933E-05" iyz="4.09549055863776E-08" izz="3.4540143384536E-05" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Wrist_Pitch_Roll.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="Wrist_Pitch_Roll.STL" /> </geometry> </collision> </link> <joint name="Wrist_Pitch" type="continuous"> <origin xyz="0 0.0052 0.1349" rpy="0 0 0" /> <parent link="Lower_Arm" /> <child link="Wrist_Pitch_Roll" /> <axis xyz="1 0 0" /> </joint> <link name="Fixed_Jaw"> <inertial> <origin xyz="0.00552376906426563 -0.0280167153359021 0.000483582592841092" rpy="0 0 0" /> <mass value="0.0929859131176897" /> <inertia ixx="4.3328249304211E-05" ixy="7.09654328670947E-06" ixz="5.99838530879484E-07" iyy="3.04451747368212E-05" iyz="-1.58743247545413E-07" izz="5.02460913506734E-05" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Wrist_Roll_Follower_SO101.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="Wrist_Roll_Follower_SO101.STL" /> </geometry> </collision> </link> <joint name="Wrist_Roll" type="continuous"> <origin xyz="0 -0.0601 0" rpy="0 0 0" /> <parent link="Wrist_Pitch_Roll" /> <child link="Fixed_Jaw" /> <axis xyz="0 1 0" /> </joint> <link name="Moving Jaw"> <inertial> <origin xyz="-0.00161744605468241 -0.0303472584046471 0.000449645961853651" rpy="0 0 0" /> <mass value="0.0202443794940372" /> <inertia ixx="1.10911325081525E-05" ixy="-5.35076503033314E-07" ixz="-9.46105662101403E-09" iyy="3.03576451001973E-06" iyz="-1.71146075110632E-07" izz="8.9916083370498E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="Moving_Jaw_SO101.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="Moving_Jaw_SO101.STL" /> </geometry> </collision> </link> <joint name="Jaw" type="continuous"> <origin xyz="-0.0202 -0.0244 0" rpy="3.1416 0 3.1416" /> <parent link="Fixed_Jaw" /> <child link="Moving Jaw" /> <axis xyz="0 0 1" /> </joint> </robot>