Feat/add urdf (#70)

Add back in Urdf so100
This commit is contained in:
Pepijn
2025-04-28 16:37:44 +02:00
committed by GitHub
parent 7e4fb1e297
commit b07b374f4d
46 changed files with 6812 additions and 0 deletions

View File

@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(SO_5DOF_ARM100_05d.SLDASM)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@@ -0,0 +1 @@
controller_joint_names: ['', 'Shoulder_Rotation', 'Shoulder_Pitch', 'Elbow', 'Wrist_Pitch', 'Wrist_Roll', 'Gripper', ]

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find SO_5DOF_ARM100_05d.SLDASM)/urdf/SO_5DOF_ARM100_05d.SLDASM.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find SO_5DOF_ARM100_05d.SLDASM)/urdf.rviz" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find SO_5DOF_ARM100_05d.SLDASM)/urdf/SO_5DOF_ARM100_05d.SLDASM.urdf -urdf -model SO_5DOF_ARM100_05d.SLDASM"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -0,0 +1,21 @@
<package format="2">
<name>SO_5DOF_ARM100_05d.SLDASM</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for SO_5DOF_ARM100_05d.SLDASM</p>
<p>This package contains configuration data, 3D models and launch files
for SO_5DOF_ARM100_05d.SLDASM robot</p>
</description>
<author>TODO</author>
<maintainer email="TODO@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>

View File

@@ -0,0 +1,8 @@
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
Base,-1.55220299024015E-10,0.0275980388649202,0.0272094138963763,0,0,0,0.146962928243327,9.5191642834079E-05,2.02405274856147E-12,1.46514387606669E-13,0.000123785814019492,1.84608762035329E-05,0.000137926707148466,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Base.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Base.STL,,Base_03-1;STS3215_02a-5,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
Shoulder_Rotation_Pitch,-0.00511938391873139,0.0678779339349912,-0.000127472379243391,0,0,0,0.111780100254674,7.03890301713851E-05,-1.55093016866869E-05,1.67387694867946E-07,3.32352621027575E-05,9.30705606418705E-07,7.08694473647387E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_Rotation_Pitch.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_Rotation_Pitch.STL,,Rotation_Pitch_04c-2;STS3215_02a-4,Origin_Shoulder_Rotation,Axis_Shoulder_Rotation,Shoulder_Rotation,continuous,0,-0.0452,0.0181,1.5708,0,1.5708,Base,0,1,0,,,,,,,,,,,,
Upper_Arm,-0.0693113774468845,0.00293741346964818,-7.61279219025209E-07,0,0,0,0.167601391353176,7.75332201021328E-05,-2.10765620509824E-06,7.52685919931984E-07,0.000233751202018378,-1.63496162538793E-07,0.000180452754687364,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Upper_Arm.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Upper_Arm.STL,,SO_ARM100_06b-5;STS3215_02a-3,Origin_Shoulder_Pitch,Axis_Shoulder_Pitch,Shoulder_Pitch,continuous,0.000125,0.1086,0,3.1416,0,-1.5708,Shoulder_Rotation_Pitch,0,0,1,,,,,,,,,,,,
Lower_Arm,-0.0588290275819227,0.0021495318374051,0.000146772621039401,0,0,0,0.142523221917339,6.29078989235053E-05,3.79294618448135E-06,1.70733512134003E-06,0.000146811163948232,-2.1474403445678E-07,0.000102145070617562,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Lower_Arm.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Lower_Arm.STL,,SO_ARM100_06b-6;STS3215_02a-6,Origin_Elbow,Axis_Elbow,Elbow,continuous,-0.11238,0.0282,0,0,0,-2.2391,Upper_Arm,0,0,1,,,,,,,,,,,,
Wrist_Pitch_Roll,-6.28656116854598E-09,-0.0087849429576346,-0.0309177852835532,0,0,0,0.106401896179987,4.78947074364113E-05,-1.33871782943846E-11,-8.95740683864277E-12,7.01088408487287E-05,-5.49748507471695E-06,6.17958653539553E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Wrist_Pitch_Roll.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Wrist_Pitch_Roll.STL,,Wrist_Roll_Pitch_04c-2;STS3215_02a-7,Origin_Wrist_Pitch,Axis_Wrist_Pitch,Wrist_Pitch,continuous,-0.1102,0.005375,0,0.90254,1.5708,0,Lower_Arm,1,0,0,,,,,,,,,,,,
Fixed_Gripper,-0.00772179942650385,-0.000555295978140996,0.0316941559340959,0,0,0,0.11710741874408,5.67526018031759E-05,1.04098982658207E-06,8.53596077253277E-06,5.78441834179299E-05,-2.86014969245207E-07,4.22399193495317E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.STL,,Wrist_Roll_05g-1;STS3215_02a-8;Removable_Jaws_01e-1,Origin_Wrist_Roll,Axis_Wrist_Roll,Wrist_Roll,continuous,0,0.002,-0.0545,3.1416,0,3.1416,Wrist_Pitch_Roll,0,0,1,,,,,,,,,,,,
Moving_Jaw,-0.0033838985185846,-0.0322884362122416,0.000144458547748166,0,0,0,0.0347149174448153,1.36949844449711E-05,-5.63192124555278E-07,-5.74449907399212E-09,7.04089001130743E-06,-1.05361496046931E-07,8.28976960805291E-06,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.STL,,Moving_Jaw_04f-1;Removable_Jaws_01e-2,Origin_Gripper,Axis_Gripper,Gripper,continuous,0.0202,0,0.024375,-1.5708,0,0,Fixed_Gripper,0,0,1,,,,,,,,,,,,
1 Link Name Center of Mass X Center of Mass Y Center of Mass Z Center of Mass Roll Center of Mass Pitch Center of Mass Yaw Mass Moment Ixx Moment Ixy Moment Ixz Moment Iyy Moment Iyz Moment Izz Visual X Visual Y Visual Z Visual Roll Visual Pitch Visual Yaw Mesh Filename Color Red Color Green Color Blue Color Alpha Collision X Collision Y Collision Z Collision Roll Collision Pitch Collision Yaw Collision Mesh Filename Material Name SW Components Coordinate System Axis Name Joint Name Joint Type Joint Origin X Joint Origin Y Joint Origin Z Joint Origin Roll Joint Origin Pitch Joint Origin Yaw Parent Joint Axis X Joint Axis Y Joint Axis Z Limit Effort Limit Velocity Limit Lower Limit Upper Calibration rising Calibration falling Dynamics Damping Dynamics Friction Safety Soft Upper Safety Soft Lower Safety K Position Safety K Velocity
2 Base -1.55220299024015E-10 0.0275980388649202 0.0272094138963763 0 0 0 0.146962928243327 9.5191642834079E-05 2.02405274856147E-12 1.46514387606669E-13 0.000123785814019492 1.84608762035329E-05 0.000137926707148466 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Base.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Base.STL Base_03-1;STS3215_02a-5 Origin_global 0 0 0 0 0 0 0 0 0
3 Shoulder_Rotation_Pitch -0.00511938391873139 0.0678779339349912 -0.000127472379243391 0 0 0 0.111780100254674 7.03890301713851E-05 -1.55093016866869E-05 1.67387694867946E-07 3.32352621027575E-05 9.30705606418705E-07 7.08694473647387E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_Rotation_Pitch.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_Rotation_Pitch.STL Rotation_Pitch_04c-2;STS3215_02a-4 Origin_Shoulder_Rotation Axis_Shoulder_Rotation Shoulder_Rotation continuous 0 -0.0452 0.0181 1.5708 0 1.5708 Base 0 1 0
4 Upper_Arm -0.0693113774468845 0.00293741346964818 -7.61279219025209E-07 0 0 0 0.167601391353176 7.75332201021328E-05 -2.10765620509824E-06 7.52685919931984E-07 0.000233751202018378 -1.63496162538793E-07 0.000180452754687364 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Upper_Arm.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Upper_Arm.STL SO_ARM100_06b-5;STS3215_02a-3 Origin_Shoulder_Pitch Axis_Shoulder_Pitch Shoulder_Pitch continuous 0.000125 0.1086 0 3.1416 0 -1.5708 Shoulder_Rotation_Pitch 0 0 1
5 Lower_Arm -0.0588290275819227 0.0021495318374051 0.000146772621039401 0 0 0 0.142523221917339 6.29078989235053E-05 3.79294618448135E-06 1.70733512134003E-06 0.000146811163948232 -2.1474403445678E-07 0.000102145070617562 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Lower_Arm.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Lower_Arm.STL SO_ARM100_06b-6;STS3215_02a-6 Origin_Elbow Axis_Elbow Elbow continuous -0.11238 0.0282 0 0 0 -2.2391 Upper_Arm 0 0 1
6 Wrist_Pitch_Roll -6.28656116854598E-09 -0.0087849429576346 -0.0309177852835532 0 0 0 0.106401896179987 4.78947074364113E-05 -1.33871782943846E-11 -8.95740683864277E-12 7.01088408487287E-05 -5.49748507471695E-06 6.17958653539553E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Wrist_Pitch_Roll.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Wrist_Pitch_Roll.STL Wrist_Roll_Pitch_04c-2;STS3215_02a-7 Origin_Wrist_Pitch Axis_Wrist_Pitch Wrist_Pitch continuous -0.1102 0.005375 0 0.90254 1.5708 0 Lower_Arm 1 0 0
7 Fixed_Gripper -0.00772179942650385 -0.000555295978140996 0.0316941559340959 0 0 0 0.11710741874408 5.67526018031759E-05 1.04098982658207E-06 8.53596077253277E-06 5.78441834179299E-05 -2.86014969245207E-07 4.22399193495317E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.STL Wrist_Roll_05g-1;STS3215_02a-8;Removable_Jaws_01e-1 Origin_Wrist_Roll Axis_Wrist_Roll Wrist_Roll continuous 0 0.002 -0.0545 3.1416 0 3.1416 Wrist_Pitch_Roll 0 0 1
8 Moving_Jaw -0.0033838985185846 -0.0322884362122416 0.000144458547748166 0 0 0 0.0347149174448153 1.36949844449711E-05 -5.63192124555278E-07 -5.74449907399212E-09 7.04089001130743E-06 -1.05361496046931E-07 8.28976960805291E-06 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.STL Moving_Jaw_04f-1;Removable_Jaws_01e-2 Origin_Gripper Axis_Gripper Gripper continuous 0.0202 0 0.024375 -1.5708 0 0 Fixed_Gripper 0 0 1

View File

@@ -0,0 +1,365 @@
<?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_05d.SLDASM">
<link
name="Base">
<inertial>
<origin
xyz="-1.55220299024015E-10 0.0275980388649202 0.0272094138963763"
rpy="0 0 0" />
<mass
value="0.146962928243327" />
<inertia
ixx="9.5191642834079E-05"
ixy="2.02405274856147E-12"
ixz="1.46514387606669E-13"
iyy="0.000123785814019492"
iyz="1.84608762035329E-05"
izz="0.000137926707148466" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/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="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Base.STL" />
</geometry>
</collision>
</link>
<link
name="Shoulder_Rotation_Pitch">
<inertial>
<origin
xyz="-0.00511938391873139 0.0678779339349912 -0.000127472379243391"
rpy="0 0 0" />
<mass
value="0.111780100254674" />
<inertia
ixx="7.03890301713851E-05"
ixy="-1.55093016866869E-05"
ixz="1.67387694867946E-07"
iyy="3.32352621027575E-05"
iyz="9.30705606418705E-07"
izz="7.08694473647387E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_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="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Shoulder_Rotation_Pitch.STL" />
</geometry>
</collision>
</link>
<joint
name="Shoulder_Rotation"
type="continuous">
<origin
xyz="0 -0.0452 0.0181"
rpy="1.5708 0 1.5708" />
<parent
link="Base" />
<child
link="Shoulder_Rotation_Pitch" />
<axis
xyz="0 1 0" />
</joint>
<link
name="Upper_Arm">
<inertial>
<origin
xyz="-0.0693113774468845 0.00293741346964818 -7.61279219025209E-07"
rpy="0 0 0" />
<mass
value="0.167601391353176" />
<inertia
ixx="7.75332201021328E-05"
ixy="-2.10765620509824E-06"
ixz="7.52685919931984E-07"
iyy="0.000233751202018378"
iyz="-1.63496162538793E-07"
izz="0.000180452754687364" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/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="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Upper_Arm.STL" />
</geometry>
</collision>
</link>
<joint
name="Shoulder_Pitch"
type="continuous">
<origin
xyz="0.000125 0.1086 0"
rpy="3.1416 0 -1.5708" />
<parent
link="Shoulder_Rotation_Pitch" />
<child
link="Upper_Arm" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Lower_Arm">
<inertial>
<origin
xyz="-0.0588290275819227 0.0021495318374051 0.000146772621039401"
rpy="0 0 0" />
<mass
value="0.142523221917339" />
<inertia
ixx="6.29078989235053E-05"
ixy="3.79294618448135E-06"
ixz="1.70733512134003E-06"
iyy="0.000146811163948232"
iyz="-2.1474403445678E-07"
izz="0.000102145070617562" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/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="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Lower_Arm.STL" />
</geometry>
</collision>
</link>
<joint
name="Elbow"
type="continuous">
<origin
xyz="-0.11238 0.0282 0"
rpy="0 0 -2.2391" />
<parent
link="Upper_Arm" />
<child
link="Lower_Arm" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Wrist_Pitch_Roll">
<inertial>
<origin
xyz="-6.28656116854598E-09 -0.0087849429576346 -0.0309177852835532"
rpy="0 0 0" />
<mass
value="0.106401896179987" />
<inertia
ixx="4.78947074364113E-05"
ixy="-1.33871782943846E-11"
ixz="-8.95740683864277E-12"
iyy="7.01088408487287E-05"
iyz="-5.49748507471695E-06"
izz="6.17958653539553E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/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="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Wrist_Pitch_Roll.STL" />
</geometry>
</collision>
</link>
<joint
name="Wrist_Pitch"
type="continuous">
<origin
xyz="-0.1102 0.005375 0"
rpy="0.90254 1.5708 0" />
<parent
link="Lower_Arm" />
<child
link="Wrist_Pitch_Roll" />
<axis
xyz="1 0 0" />
</joint>
<link
name="Fixed_Gripper">
<inertial>
<origin
xyz="-0.00772179942650385 -0.000555295978140996 0.0316941559340959"
rpy="0 0 0" />
<mass
value="0.11710741874408" />
<inertia
ixx="5.67526018031759E-05"
ixy="1.04098982658207E-06"
ixz="8.53596077253277E-06"
iyy="5.78441834179299E-05"
iyz="-2.86014969245207E-07"
izz="4.22399193495317E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.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://SO_5DOF_ARM100_05d.SLDASM/meshes/Fixed_Gripper.STL" />
</geometry>
</collision>
</link>
<joint
name="Wrist_Roll"
type="continuous">
<origin
xyz="0 0.002 -0.0545"
rpy="3.1416 0 3.1416" />
<parent
link="Wrist_Pitch_Roll" />
<child
link="Fixed_Gripper" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Moving_Jaw">
<inertial>
<origin
xyz="-0.0033838985185846 -0.0322884362122416 0.000144458547748166"
rpy="0 0 0" />
<mass
value="0.0347149174448153" />
<inertia
ixx="1.36949844449711E-05"
ixy="-5.63192124555278E-07"
ixz="-5.74449907399212E-09"
iyy="7.04089001130743E-06"
iyz="-1.05361496046931E-07"
izz="8.28976960805291E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.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://SO_5DOF_ARM100_05d.SLDASM/meshes/Moving_Jaw.STL" />
</geometry>
</collision>
</link>
<joint
name="Gripper"
type="continuous">
<origin
xyz="0.0202 0 0.024375"
rpy="-1.5708 0 0" />
<parent
link="Fixed_Gripper" />
<child
link="Moving_Jaw" />
<axis
xyz="0 0 1" />
</joint>
</robot>

View File

@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(SO_5DOF_ARM100_8j_URDF.SLDASM)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@@ -0,0 +1 @@
controller_joint_names: ['', 'Rotation', 'Pitch', 'Elbow', 'Wrist_Pitch', 'Wrist_Roll', 'Jaw', ]

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find SO_5DOF_ARM100_8j_URDF.SLDASM)/urdf/SO_5DOF_ARM100_8j_URDF.SLDASM.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find SO_5DOF_ARM100_8j_URDF.SLDASM)/urdf.rviz" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find SO_5DOF_ARM100_8j_URDF.SLDASM)/urdf/SO_5DOF_ARM100_8j_URDF.SLDASM.urdf -urdf -model SO_5DOF_ARM100_8j_URDF.SLDASM"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

Binary file not shown.

View File

@@ -0,0 +1,21 @@
<package format="2">
<name>SO_5DOF_ARM100_8j_URDF.SLDASM</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for SO_5DOF_ARM100_8j_URDF.SLDASM</p>
<p>This package contains configuration data, 3D models and launch files
for SO_5DOF_ARM100_8j_URDF.SLDASM robot</p>
</description>
<author>TODO</author>
<maintainer email="TODO@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>

View File

@@ -0,0 +1,8 @@
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
Base,-2.45960666746703E-07,0.0311418169687909,0.0175746661003382,0,0,0,0.193184127927598,0.000137030709467877,2.10136126944992E-08,4.24087422551286E-09,0.000169089551209259,2.26514711036514E-05,0.000145097720857224,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Base.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Base.STL,,SO_5DOF_ARM100_08j_Base-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
Rotation_Pitch,-9.07886224712597E-05,0.0590971820568318,0.031089016892169,0,0,0,0.119226314127197,5.90408775624429E-05,4.90800532852998E-07,-5.90451772654387E-08,3.21498601038881E-05,-4.58026206663885E-06,5.86058514263952E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Rotation_Pitch.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Rotation_Pitch.STL,,SO_5DOF_ARM100_08j_Rotation_Pitch-1,Origin_Rotation,Axis_Rotation,Rotation,continuous,0,-0.0452,0.0165,1.5708,0,0,Base,0,1,0,,,,,,,,,,,,
Upper_Arm,-1.7205170190925E-05,0.0701802156327694,0.00310545118155671,0,0,0,0.162409284599177,0.000167153146617081,1.03902689187701E-06,-1.20161820645189E-08,7.01946992214245E-05,2.11884806298698E-06,0.000213280241160769,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Upper_Arm.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Upper_Arm.STL,,SO_5DOF_ARM100_08j_Upper_Arm-1,Origin_Pitch,Axis_Pitch,Pitch,continuous,0,0.1025,0.0306,0,0,0,Rotation_Pitch,1,0,0,,,,,,,,,,,,
Lower_Arm,-0.00339603710186651,0.00137796353960074,0.0768006751156044,0,0,0,0.147967774582291,0.000105333995841409,1.73059237226499E-07,-1.1720305455211E-05,0.000138766654485212,1.77429964684103E-06,5.08741652515214E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Lower_Arm.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Lower_Arm.STL,,SO_5DOF_ARM100_08j_Lower_Arm-1,Origin_Elbow,Axis_Elbow,Elbow,continuous,0,0.11257,0.028,0,0,0,Upper_Arm,1,0,0,,,,,,,,,,,,
Wrist_Pitch_Roll,-0.00852653127372418,-0.0352278997897927,-2.34622481569413E-05,0,0,0,0.066132067097723,1.95717492443445E-05,-6.62714374412293E-07,5.20089016442066E-09,2.38028417569933E-05,4.09549055863776E-08,3.4540143384536E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Wrist_Pitch_Roll.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Wrist_Pitch_Roll.STL,,SO_5DOF_ARM100_08j_Wrist_Roll_Pitch-1,Origin_Wrist_Pitch,Axis_Wrist_Pitch,Wrist_Pitch,continuous,0,0.0052,0.1349,0,0,0,Lower_Arm,1,0,0,,,,,,,,,,,,
Fixed_Jaw,0.00552376906426563,-0.0280167153359021,0.000483582592841092,0,0,0,0.0929859131176897,4.3328249304211E-05,7.09654328670947E-06,5.99838530879484E-07,3.04451747368212E-05,-1.58743247545413E-07,5.02460913506734E-05,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.STL,,SO_5DOF_ARM100_08j_Fixed_Jaw-1,Origin_Wrist_Roll,Axis_Wrist_Roll,Wrist_Roll,continuous,0,-0.0601,0,0,0,0,Wrist_Pitch_Roll,0,1,0,,,,,,,,,,,,
Moving Jaw,-0.00161744605468241,-0.0303472584046471,0.000449645961853651,0,0,0,0.0202443794940372,1.10911325081525E-05,-5.35076503033314E-07,-9.46105662101403E-09,3.03576451001973E-06,-1.71146075110632E-07,8.9916083370498E-06,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.STL,,Moving_Jaw_08c-1,Origin_Jaw,Axis_Jaw,Jaw,continuous,-0.0202,-0.0244,0,3.1416,0,3.1416,Fixed_Jaw,0,0,1,,,,,,,,,,,,
1 Link Name Center of Mass X Center of Mass Y Center of Mass Z Center of Mass Roll Center of Mass Pitch Center of Mass Yaw Mass Moment Ixx Moment Ixy Moment Ixz Moment Iyy Moment Iyz Moment Izz Visual X Visual Y Visual Z Visual Roll Visual Pitch Visual Yaw Mesh Filename Color Red Color Green Color Blue Color Alpha Collision X Collision Y Collision Z Collision Roll Collision Pitch Collision Yaw Collision Mesh Filename Material Name SW Components Coordinate System Axis Name Joint Name Joint Type Joint Origin X Joint Origin Y Joint Origin Z Joint Origin Roll Joint Origin Pitch Joint Origin Yaw Parent Joint Axis X Joint Axis Y Joint Axis Z Limit Effort Limit Velocity Limit Lower Limit Upper Calibration rising Calibration falling Dynamics Damping Dynamics Friction Safety Soft Upper Safety Soft Lower Safety K Position Safety K Velocity
2 Base -2.45960666746703E-07 0.0311418169687909 0.0175746661003382 0 0 0 0.193184127927598 0.000137030709467877 2.10136126944992E-08 4.24087422551286E-09 0.000169089551209259 2.26514711036514E-05 0.000145097720857224 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Base.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Base.STL SO_5DOF_ARM100_08j_Base-1 Origin_global 0 0 0 0 0 0 0 0 0
3 Rotation_Pitch -9.07886224712597E-05 0.0590971820568318 0.031089016892169 0 0 0 0.119226314127197 5.90408775624429E-05 4.90800532852998E-07 -5.90451772654387E-08 3.21498601038881E-05 -4.58026206663885E-06 5.86058514263952E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Rotation_Pitch.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Rotation_Pitch.STL SO_5DOF_ARM100_08j_Rotation_Pitch-1 Origin_Rotation Axis_Rotation Rotation continuous 0 -0.0452 0.0165 1.5708 0 0 Base 0 1 0
4 Upper_Arm -1.7205170190925E-05 0.0701802156327694 0.00310545118155671 0 0 0 0.162409284599177 0.000167153146617081 1.03902689187701E-06 -1.20161820645189E-08 7.01946992214245E-05 2.11884806298698E-06 0.000213280241160769 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Upper_Arm.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Upper_Arm.STL SO_5DOF_ARM100_08j_Upper_Arm-1 Origin_Pitch Axis_Pitch Pitch continuous 0 0.1025 0.0306 0 0 0 Rotation_Pitch 1 0 0
5 Lower_Arm -0.00339603710186651 0.00137796353960074 0.0768006751156044 0 0 0 0.147967774582291 0.000105333995841409 1.73059237226499E-07 -1.1720305455211E-05 0.000138766654485212 1.77429964684103E-06 5.08741652515214E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Lower_Arm.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Lower_Arm.STL SO_5DOF_ARM100_08j_Lower_Arm-1 Origin_Elbow Axis_Elbow Elbow continuous 0 0.11257 0.028 0 0 0 Upper_Arm 1 0 0
6 Wrist_Pitch_Roll -0.00852653127372418 -0.0352278997897927 -2.34622481569413E-05 0 0 0 0.066132067097723 1.95717492443445E-05 -6.62714374412293E-07 5.20089016442066E-09 2.38028417569933E-05 4.09549055863776E-08 3.4540143384536E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Wrist_Pitch_Roll.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Wrist_Pitch_Roll.STL SO_5DOF_ARM100_08j_Wrist_Roll_Pitch-1 Origin_Wrist_Pitch Axis_Wrist_Pitch Wrist_Pitch continuous 0 0.0052 0.1349 0 0 0 Lower_Arm 1 0 0
7 Fixed_Jaw 0.00552376906426563 -0.0280167153359021 0.000483582592841092 0 0 0 0.0929859131176897 4.3328249304211E-05 7.09654328670947E-06 5.99838530879484E-07 3.04451747368212E-05 -1.58743247545413E-07 5.02460913506734E-05 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.STL SO_5DOF_ARM100_08j_Fixed_Jaw-1 Origin_Wrist_Roll Axis_Wrist_Roll Wrist_Roll continuous 0 -0.0601 0 0 0 0 Wrist_Pitch_Roll 0 1 0
8 Moving Jaw -0.00161744605468241 -0.0303472584046471 0.000449645961853651 0 0 0 0.0202443794940372 1.10911325081525E-05 -5.35076503033314E-07 -9.46105662101403E-09 3.03576451001973E-06 -1.71146075110632E-07 8.9916083370498E-06 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.STL Moving_Jaw_08c-1 Origin_Jaw Axis_Jaw Jaw continuous -0.0202 -0.0244 0 3.1416 0 3.1416 Fixed_Jaw 0 0 1

View File

@@ -0,0 +1,365 @@
<?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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.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://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Fixed_Jaw.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="package://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.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://SO_5DOF_ARM100_8j_URDF.SLDASM/meshes/Moving Jaw.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>

View File

@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@@ -0,0 +1 @@
controller_joint_names: ['', 'Shoulder_Pitch', 'Shoulder_Yaw', 'Humeral_Rotation', 'Elbow', 'Wrist_Roll', 'Wrist_Yaw', 'Wrist_Pitch', ]

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM)/urdf/SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM)/urdf.rviz" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM)/urdf/SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM.urdf -urdf -model SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

View File

@@ -0,0 +1,21 @@
<package format="2">
<name>SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM</p>
<p>This package contains configuration data, 3D models and launch files
for SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM robot</p>
</description>
<author>TODO</author>
<maintainer email="TODO@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>

View File

@@ -0,0 +1,9 @@
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
Base,0.0195624606184725,-0.0295895597276446,-2.76876897655451E-06,0,0,0,0.184098970814929,0.000142288448859702,-2.26169251313517E-05,4.23610978246252E-09,0.00016758363588302,-2.10119213746261E-08,0.000135962602722997,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Base.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Base.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_Base-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
Shoulder_Pitch_Yaw,-0.013299,0.079753,0.035058,0,0,0,0.092914,5.0472E-05,-6.879E-06,3.3863E-07,2.252E-05,5.9775E-07,5.4357E-05,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_PR-1,Origin_Shoulder_Pitch,Axis_Shoulder_Pitch,Shoulder_Pitch,continuous,0.01,0,0,-1.5708,0,-1.5723,Base,0,1,0,0,0,-1,3,,,,,,,,
Upper_Humeral,-0.045255,0.0065486,0.04097,0,0,0,0.21817,9.4379E-05,1.3581E-05,2.8938E-05,0.00021514,-3.2154E-06,0.00014492,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_UH-1,Origin_Shoulder_Yaw,Axis_Shoulder_Yaw,Shoulder_Yaw,continuous,-0.002,0.123,0,-0.00019451,1.2429E-05,0.12763,Shoulder_Pitch_Yaw,0.0015282,0,-1,0,0,-1,0,,,,,,,,
Humeral_Elbow,-0.072262,0.021725,-0.0207,0,0,0,0.16611,5.0858E-05,1.3362E-05,-2.4207E-06,0.00013739,2.7097E-06,0.00013639,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_HE-1,Origin_Humeral_Rotation,Axis_Humeral_Rotation,Humeral_Rotation,continuous,-0.090614,0.016864,0.034762,-0.53649,0.06528,-0.018789,Upper_Humeral,0.99187,-0.12728,0.0015157,0,0,-1.8,1.8,,,,,,,,
Forearm,-0.02921,0.0068798,0.0036776,0,0,0,0.074077,3.2764E-05,-2.3726E-06,-2.325E-06,1.9912E-05,-1.1135E-05,3.1909E-05,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_FOREARM-1,Origin_Elbow,Axis_Elbow,Elbow,continuous,-0.10713,0.0094948,0.0068692,0.0028871,0.021537,0.013065,Humeral_Elbow,0.10838,0.8507,0.51436,0,0,-3,0,,,,,,,,
Wrist_Roll_Yaw,-0.053889,0.0079735,-0.00086939,0,0,0,0.091826,1.7943E-05,1.5108E-06,-1.3157E-06,3.104E-05,-2.7449E-06,2.922E-05,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_W_ROLL-1,Origin_Wrist_Roll,Axis_Wrist_Roll,Wrist_Roll,continuous,-0.058273,0.0045968,0.0025376,2.7435,-0.099808,-0.26118,Forearm,0.98986,-0.14016,0.023243,0,0,-1.8,1.8,,,,,,,,
Wrist_Yaw_Pitch,2.7756E-17,0.0024,0.0045832,0,0,0,0.023922,8.3081E-06,6.951E-21,-4.473E-21,1.0623E-05,-8.225E-21,1.3498E-05,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL,,SO_7DOF_ARM100_08h_HL_01d_URDF_WYP-2,Origin_Wrist_Yaw,Axis_Wrist_Yaw,Wrist_Yaw,continuous,-0.094575,0.013474,-0.0022794,1.5994,-0.62299,-1.7282,Wrist_Roll_Yaw,0,1,0,0,0,-0.9,0.5,,,,,,,,
End_Servo,-0.012801,-1.9931E-09,0.00037293,0,0,0,0.036217,5.0606E-06,-1.1965E-12,7.0946E-08,9.3616E-06,1.0572E-12,7.8391E-06,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL,,STS3215_03a-23,Origin_Wrist_Pitch,Axis_Wrist_Pitch,Wrist_Pitch,continuous,0,0.0024,0.025,0,1.5708,0,Wrist_Yaw_Pitch,0,0,1,0,0,-1.8,1.8,,,,,,,,
1 Link Name Center of Mass X Center of Mass Y Center of Mass Z Center of Mass Roll Center of Mass Pitch Center of Mass Yaw Mass Moment Ixx Moment Ixy Moment Ixz Moment Iyy Moment Iyz Moment Izz Visual X Visual Y Visual Z Visual Roll Visual Pitch Visual Yaw Mesh Filename Color Red Color Green Color Blue Color Alpha Collision X Collision Y Collision Z Collision Roll Collision Pitch Collision Yaw Collision Mesh Filename Material Name SW Components Coordinate System Axis Name Joint Name Joint Type Joint Origin X Joint Origin Y Joint Origin Z Joint Origin Roll Joint Origin Pitch Joint Origin Yaw Parent Joint Axis X Joint Axis Y Joint Axis Z Limit Effort Limit Velocity Limit Lower Limit Upper Calibration rising Calibration falling Dynamics Damping Dynamics Friction Safety Soft Upper Safety Soft Lower Safety K Position Safety K Velocity
2 Base 0.0195624606184725 -0.0295895597276446 -2.76876897655451E-06 0 0 0 0.184098970814929 0.000142288448859702 -2.26169251313517E-05 4.23610978246252E-09 0.00016758363588302 -2.10119213746261E-08 0.000135962602722997 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Base.STL 0.792156862745098 0.819607843137255 0.933333333333333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Base.STL SO_7DOF_ARM100_08h_HL_01d_URDF_Base-1 Origin_global 0 0 0 0 0 0 0 0 0
3 Shoulder_Pitch_Yaw -0.013299 0.079753 0.035058 0 0 0 0.092914 5.0472E-05 -6.879E-06 3.3863E-07 2.252E-05 5.9775E-07 5.4357E-05 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL SO_7DOF_ARM100_08h_HL_01d_URDF_PR-1 Origin_Shoulder_Pitch Axis_Shoulder_Pitch Shoulder_Pitch continuous 0.01 0 0 -1.5708 0 -1.5723 Base 0 1 0 0 0 -1 3
4 Upper_Humeral -0.045255 0.0065486 0.04097 0 0 0 0.21817 9.4379E-05 1.3581E-05 2.8938E-05 0.00021514 -3.2154E-06 0.00014492 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL SO_7DOF_ARM100_08h_HL_01d_URDF_UH-1 Origin_Shoulder_Yaw Axis_Shoulder_Yaw Shoulder_Yaw continuous -0.002 0.123 0 -0.00019451 1.2429E-05 0.12763 Shoulder_Pitch_Yaw 0.0015282 0 -1 0 0 -1 0
5 Humeral_Elbow -0.072262 0.021725 -0.0207 0 0 0 0.16611 5.0858E-05 1.3362E-05 -2.4207E-06 0.00013739 2.7097E-06 0.00013639 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL SO_7DOF_ARM100_08h_HL_01d_URDF_HE-1 Origin_Humeral_Rotation Axis_Humeral_Rotation Humeral_Rotation continuous -0.090614 0.016864 0.034762 -0.53649 0.06528 -0.018789 Upper_Humeral 0.99187 -0.12728 0.0015157 0 0 -1.8 1.8
6 Forearm -0.02921 0.0068798 0.0036776 0 0 0 0.074077 3.2764E-05 -2.3726E-06 -2.325E-06 1.9912E-05 -1.1135E-05 3.1909E-05 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL SO_7DOF_ARM100_08h_HL_01d_URDF_FOREARM-1 Origin_Elbow Axis_Elbow Elbow continuous -0.10713 0.0094948 0.0068692 0.0028871 0.021537 0.013065 Humeral_Elbow 0.10838 0.8507 0.51436 0 0 -3 0
7 Wrist_Roll_Yaw -0.053889 0.0079735 -0.00086939 0 0 0 0.091826 1.7943E-05 1.5108E-06 -1.3157E-06 3.104E-05 -2.7449E-06 2.922E-05 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL SO_7DOF_ARM100_08h_HL_01d_URDF_W_ROLL-1 Origin_Wrist_Roll Axis_Wrist_Roll Wrist_Roll continuous -0.058273 0.0045968 0.0025376 2.7435 -0.099808 -0.26118 Forearm 0.98986 -0.14016 0.023243 0 0 -1.8 1.8
8 Wrist_Yaw_Pitch 2.7756E-17 0.0024 0.0045832 0 0 0 0.023922 8.3081E-06 6.951E-21 -4.473E-21 1.0623E-05 -8.225E-21 1.3498E-05 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL SO_7DOF_ARM100_08h_HL_01d_URDF_WYP-2 Origin_Wrist_Yaw Axis_Wrist_Yaw Wrist_Yaw continuous -0.094575 0.013474 -0.0022794 1.5994 -0.62299 -1.7282 Wrist_Roll_Yaw 0 1 0 0 0 -0.9 0.5
9 End_Servo -0.012801 -1.9931E-09 0.00037293 0 0 0 0.036217 5.0606E-06 -1.1965E-12 7.0946E-08 9.3616E-06 1.0572E-12 7.8391E-06 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL 0.79216 0.81961 0.93333 1 0 0 0 0 0 0 package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL STS3215_03a-23 Origin_Wrist_Pitch Axis_Wrist_Pitch Wrist_Pitch continuous 0 0.0024 0.025 0 1.5708 0 Wrist_Yaw_Pitch 0 0 1 0 0 -1.8 1.8

View File

@@ -0,0 +1,453 @@
<?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_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM">
<link
name="Base">
<inertial>
<origin
xyz="0.0195624606184725 -0.0295895597276446 -2.76876897655451E-06"
rpy="0 0 0" />
<mass
value="0.184098970814929" />
<inertia
ixx="0.000142288448859702"
ixy="-2.26169251313517E-05"
ixz="4.23610978246252E-09"
iyy="0.00016758363588302"
iyz="-2.10119213746261E-08"
izz="0.000135962602722997" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/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="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Base.STL" />
</geometry>
</collision>
</link>
<link
name="Shoulder_Pitch_Yaw">
<inertial>
<origin
xyz="-0.013299 0.079753 0.035058"
rpy="0 0 0" />
<mass
value="0.092914" />
<inertia
ixx="5.0472E-05"
ixy="-6.879E-06"
ixz="3.3863E-07"
iyy="2.252E-05"
iyz="5.9775E-07"
izz="5.4357E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Shoulder_Pitch_Yaw.STL" />
</geometry>
</collision>
</link>
<joint
name="Shoulder_Pitch"
type="continuous">
<origin
xyz="0.01 0 0"
rpy="-1.5708 0 -1.5723" />
<parent
link="Base" />
<child
link="Shoulder_Pitch_Yaw" />
<axis
xyz="0 1 0" />
<limit
lower="-1"
upper="3"
effort="0"
velocity="0" />
</joint>
<link
name="Upper_Humeral">
<inertial>
<origin
xyz="-0.045255 0.0065486 0.04097"
rpy="0 0 0" />
<mass
value="0.21817" />
<inertia
ixx="9.4379E-05"
ixy="1.3581E-05"
ixz="2.8938E-05"
iyy="0.00021514"
iyz="-3.2154E-06"
izz="0.00014492" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Upper_Humeral.STL" />
</geometry>
</collision>
</link>
<joint
name="Shoulder_Yaw"
type="continuous">
<origin
xyz="-0.002 0.123 0"
rpy="-0.00019451 1.2429E-05 0.12763" />
<parent
link="Shoulder_Pitch_Yaw" />
<child
link="Upper_Humeral" />
<axis
xyz="0.0015282 0 -1" />
<limit
lower="-1"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="Humeral_Elbow">
<inertial>
<origin
xyz="-0.072262 0.021725 -0.0207"
rpy="0 0 0" />
<mass
value="0.16611" />
<inertia
ixx="5.0858E-05"
ixy="1.3362E-05"
ixz="-2.4207E-06"
iyy="0.00013739"
iyz="2.7097E-06"
izz="0.00013639" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Humeral_Elbow.STL" />
</geometry>
</collision>
</link>
<joint
name="Humeral_Rotation"
type="continuous">
<origin
xyz="-0.090614 0.016864 0.034762"
rpy="-0.53649 0.06528 -0.018789" />
<parent
link="Upper_Humeral" />
<child
link="Humeral_Elbow" />
<axis
xyz="0.99187 -0.12728 0.0015157" />
<limit
lower="-1.8"
upper="1.8"
effort="0"
velocity="0" />
</joint>
<link
name="Forearm">
<inertial>
<origin
xyz="-0.02921 0.0068798 0.0036776"
rpy="0 0 0" />
<mass
value="0.074077" />
<inertia
ixx="3.2764E-05"
ixy="-2.3726E-06"
ixz="-2.325E-06"
iyy="1.9912E-05"
iyz="-1.1135E-05"
izz="3.1909E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Forearm.STL" />
</geometry>
</collision>
</link>
<joint
name="Elbow"
type="continuous">
<origin
xyz="-0.10713 0.0094948 0.0068692"
rpy="0.0028871 0.021537 0.013065" />
<parent
link="Humeral_Elbow" />
<child
link="Forearm" />
<axis
xyz="0.10838 0.8507 0.51436" />
<limit
lower="-3"
upper="0"
effort="0"
velocity="0" />
</joint>
<link
name="Wrist_Roll_Yaw">
<inertial>
<origin
xyz="-0.053889 0.0079735 -0.00086939"
rpy="0 0 0" />
<mass
value="0.091826" />
<inertia
ixx="1.7943E-05"
ixy="1.5108E-06"
ixz="-1.3157E-06"
iyy="3.104E-05"
iyz="-2.7449E-06"
izz="2.922E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Roll_Yaw.STL" />
</geometry>
</collision>
</link>
<joint
name="Wrist_Roll"
type="continuous">
<origin
xyz="-0.058273 0.0045968 0.0025376"
rpy="2.7435 -0.099808 -0.26118" />
<parent
link="Forearm" />
<child
link="Wrist_Roll_Yaw" />
<axis
xyz="0.98986 -0.14016 0.023243" />
<limit
lower="-1.8"
upper="1.8"
effort="0"
velocity="0" />
</joint>
<link
name="Wrist_Yaw_Pitch">
<inertial>
<origin
xyz="2.7756E-17 0.0024 0.0045832"
rpy="0 0 0" />
<mass
value="0.023922" />
<inertia
ixx="8.3081E-06"
ixy="6.951E-21"
ixz="-4.473E-21"
iyy="1.0623E-05"
iyz="-8.225E-21"
izz="1.3498E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/Wrist_Yaw_Pitch.STL" />
</geometry>
</collision>
</link>
<joint
name="Wrist_Yaw"
type="continuous">
<origin
xyz="-0.094575 0.013474 -0.0022794"
rpy="1.5994 -0.62299 -1.7282" />
<parent
link="Wrist_Roll_Yaw" />
<child
link="Wrist_Yaw_Pitch" />
<axis
xyz="0 1 0" />
<limit
lower="-0.9"
upper="0.5"
effort="0"
velocity="0" />
</joint>
<link
name="End_Servo">
<inertial>
<origin
xyz="-0.012801 -1.9931E-09 0.00037293"
rpy="0 0 0" />
<mass
value="0.036217" />
<inertia
ixx="5.0606E-06"
ixy="-1.1965E-12"
ixz="7.0946E-08"
iyy="9.3616E-06"
iyz="1.0572E-12"
izz="7.8391E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://SO_7DOF_ARM100_08h_HL_01d_URDF_01.SLDASM/meshes/End_Servo.STL" />
</geometry>
</collision>
</link>
<joint
name="Wrist_Pitch"
type="continuous">
<origin
xyz="0 0.0024 0.025"
rpy="0 1.5708 0" />
<parent
link="Wrist_Yaw_Pitch" />
<child
link="End_Servo" />
<axis
xyz="0 0 1" />
<limit
lower="-1.8"
upper="1.8"
effort="0"
velocity="0" />
</joint>
</robot>