Добавлена urdf-модель манипулятора
BIN
img/00.jpg
Normal file
After Width: | Height: | Size: 207 KiB |
BIN
img/01.jpg
Normal file
After Width: | Height: | Size: 225 KiB |
BIN
img/01_Base_Link_01.jpg
Normal file
After Width: | Height: | Size: 205 KiB |
BIN
img/01_Base_Link_02.jpg
Normal file
After Width: | Height: | Size: 153 KiB |
BIN
img/01_Base_Link_03.jpg
Normal file
After Width: | Height: | Size: 224 KiB |
BIN
img/01_Base_Link_04.jpg
Normal file
After Width: | Height: | Size: 205 KiB |
BIN
img/02.jpg
Normal file
After Width: | Height: | Size: 204 KiB |
BIN
img/02_Fork_01.jpg
Normal file
After Width: | Height: | Size: 184 KiB |
BIN
img/02_Fork_02.jpg
Normal file
After Width: | Height: | Size: 142 KiB |
BIN
img/02_Fork_03.jpg
Normal file
After Width: | Height: | Size: 201 KiB |
BIN
img/03.jpg
Normal file
After Width: | Height: | Size: 167 KiB |
BIN
img/03_Link_01.jpg
Normal file
After Width: | Height: | Size: 205 KiB |
BIN
img/03_Link_02.jpg
Normal file
After Width: | Height: | Size: 117 KiB |
BIN
img/03_Link_03.jpg
Normal file
After Width: | Height: | Size: 230 KiB |
BIN
img/04.jpg
Normal file
After Width: | Height: | Size: 188 KiB |
BIN
img/05.jpg
Normal file
After Width: | Height: | Size: 170 KiB |
BIN
img/06.jpg
Normal file
After Width: | Height: | Size: 199 KiB |
BIN
img/07_Dock_Link_01.jpg
Normal file
After Width: | Height: | Size: 226 KiB |
BIN
img/07_Dock_Link_02.jpg
Normal file
After Width: | Height: | Size: 131 KiB |
BIN
img/07_Dock_Link_03.jpg
Normal file
After Width: | Height: | Size: 245 KiB |
|
@ -1,14 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
|
||||
project(_grip_tool)
|
||||
|
||||
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)
|
|
@ -1 +0,0 @@
|
|||
controller_joint_names: ['', 'grip_rot', 'open_1', 'open_2', ]
|
|
@ -1,20 +0,0 @@
|
|||
<launch>
|
||||
<arg
|
||||
name="model" />
|
||||
<param
|
||||
name="robot_description"
|
||||
textfile="$(find _grip_tool)/urdf/_grip_tool.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 _grip_tool)/urdf.rviz" />
|
||||
</launch>
|
|
@ -1,20 +0,0 @@
|
|||
<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 _grip_tool)/urdf/_grip_tool.urdf -urdf -model _grip_tool"
|
||||
output="screen" />
|
||||
<node
|
||||
name="fake_joint_calibration"
|
||||
pkg="rostopic"
|
||||
type="rostopic"
|
||||
args="pub /calibrated std_msgs/Bool true" />
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<package format="2">
|
||||
<name>_grip_tool</name>
|
||||
<version>1.0.0</version>
|
||||
<description>
|
||||
<p>URDF Description package for _grip_tool</p>
|
||||
<p>This package contains configuration data, 3D models and launch files
|
||||
for _grip_tool 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>
|
|
@ -1,221 +0,0 @@
|
|||
<?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="_grip_tool">
|
||||
<link
|
||||
name="Grip_Base">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.000364704367134063 0.0336387482840125 0.0593891203954369"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.13983632906086" />
|
||||
<inertia
|
||||
ixx="0.00107738806534129"
|
||||
ixy="-1.09841172461737E-05"
|
||||
ixz="2.62750043451545E-06"
|
||||
iyy="0.000717388573992299"
|
||||
iyz="-2.95426438182787E-05"
|
||||
izz="0.00115777179755934" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Grip_Base.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Grip_Base.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link
|
||||
name="Grip_Rotator">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="6.79110135283868E-11 -3.80956832067611E-10 0.00775394473595793"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.161003401535982" />
|
||||
<inertia
|
||||
ixx="0.00011089089949771"
|
||||
ixy="5.01335040610636E-06"
|
||||
ixz="1.74608448389267E-14"
|
||||
iyy="0.000105515893695012"
|
||||
iyz="-2.03282362854432E-14"
|
||||
izz="0.000206912001661452" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Grip_Rotator.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Grip_Rotator.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="grip_rot"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.10861"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Grip_Base" />
|
||||
<child
|
||||
link="Grip_Rotator" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="0"
|
||||
upper="0"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Gripper_1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.00399878118534129 0.0187296413885176 -0.0777776233934166"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.0601996441483964" />
|
||||
<inertia
|
||||
ixx="4.18533281165612E-05"
|
||||
ixy="-7.11657995951147E-06"
|
||||
ixz="1.81029223490065E-05"
|
||||
iyy="7.89886367868258E-05"
|
||||
iyz="1.20542845942065E-05"
|
||||
izz="5.16740841307935E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Gripper_1.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.752941176470588 0 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Gripper_1.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="open_1"
|
||||
type="prismatic">
|
||||
<origin
|
||||
xyz="0 0 0.1071"
|
||||
rpy="0 0 1.5708" />
|
||||
<parent
|
||||
link="Grip_Rotator" />
|
||||
<child
|
||||
link="Gripper_1" />
|
||||
<axis
|
||||
xyz="-1 0 0" />
|
||||
<limit
|
||||
lower="0"
|
||||
upper="0.064"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Gripper_2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0039988 -0.077778 -0.01873"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.0602" />
|
||||
<inertia
|
||||
ixx="4.1853E-05"
|
||||
ixy="1.8103E-05"
|
||||
ixz="7.1166E-06"
|
||||
iyy="5.1674E-05"
|
||||
iyz="-1.2054E-05"
|
||||
izz="7.8989E-05" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Gripper_2.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0 0 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://_grip_tool/meshes/Gripper_2.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="open_2"
|
||||
type="prismatic">
|
||||
<origin
|
||||
xyz="0 0 0.1071"
|
||||
rpy="1.5708 0 -1.5708" />
|
||||
<parent
|
||||
link="Grip_Rotator" />
|
||||
<child
|
||||
link="Gripper_2" />
|
||||
<axis
|
||||
xyz="-1 0 0" />
|
||||
<limit
|
||||
lower="0"
|
||||
upper="0.064"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
</robot>
|
BIN
urdf/images/Base_Link.jpg
Normal file
After Width: | Height: | Size: 205 KiB |
BIN
urdf/images/Dock_Link.jpg
Normal file
After Width: | Height: | Size: 226 KiB |
BIN
urdf/images/Fork_1,2,3.jpg
Normal file
After Width: | Height: | Size: 184 KiB |
BIN
urdf/images/Link_1,2.jpg
Normal file
After Width: | Height: | Size: 205 KiB |
BIN
urdf/meshes/collision/Base_Link.stl
Normal file
BIN
urdf/meshes/collision/Dock_Link.stl
Normal file
BIN
urdf/meshes/collision/Fork_1.stl
Normal file
BIN
urdf/meshes/collision/Fork_2.stl
Normal file
BIN
urdf/meshes/collision/Fork_3.stl
Normal file
BIN
urdf/meshes/collision/Link_1.stl
Normal file
BIN
urdf/meshes/collision/Link_2.stl
Normal file
172
urdf/meshes/visual/Base_Link.dae
Normal file
168
urdf/meshes/visual/Dock_Link.dae
Normal file
136
urdf/meshes/visual/Fork_1.dae
Normal file
136
urdf/meshes/visual/Fork_2.dae
Normal file
136
urdf/meshes/visual/Fork_3.dae
Normal file
140
urdf/meshes/visual/Link_1.dae
Normal file
140
urdf/meshes/visual/Link_2.dae
Normal file
|
@ -1,14 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
|
||||
project(arm_assembly_)
|
||||
|
||||
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)
|
|
@ -1 +0,0 @@
|
|||
controller_joint_names: ['', 'rot_1', 'rot_2', 'rot_3', 'rot_4', 'rot_5', 'rot_6', ]
|
|
@ -1,20 +0,0 @@
|
|||
<launch>
|
||||
<arg
|
||||
name="model" />
|
||||
<param
|
||||
name="robot_description"
|
||||
textfile="$(find arm_assembly_)/urdf/arm_assembly_.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 arm_assembly_)/urdf.rviz" />
|
||||
</launch>
|
|
@ -1,20 +0,0 @@
|
|||
<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 arm_assembly_)/urdf/arm_assembly_.urdf -urdf -model arm_assembly_"
|
||||
output="screen" />
|
||||
<node
|
||||
name="fake_joint_calibration"
|
||||
pkg="rostopic"
|
||||
type="rostopic"
|
||||
args="pub /calibrated std_msgs/Bool true" />
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<package format="2">
|
||||
<name>arm_assembly_</name>
|
||||
<version>1.0.0</version>
|
||||
<description>
|
||||
<p>URDF Description package for arm_assembly_</p>
|
||||
<p>This package contains configuration data, 3D models and launch files
|
||||
for arm_assembly_ 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>
|
|
@ -1,8 +0,0 @@
|
|||
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_link,"-0,000297","0,096472","-0,00036103",0,0,0,"1,8803","0,005033","0,00034382","-4,7499E-06","0,0033796","-2,3099E-05","0,0040586",0,0,0,0,0,0,package://arm_assembly_/meshes/Base_link.STL,"0,75294","0,75294","0,75294",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Base_link.STL,,asm_start_link_220707-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
||||
Fork_1,"0,0472051139085305","0,0557265410642573","-0,00208890925682975",0,0,0,"1,12472202892859","0,00367804533572758","-0,00149971410403071","-1,04277925521891E-05","0,0041832353455649","5,67049464176682E-06","0,00415208849477534",0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_1.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_1.STL,,asm_fork_220606-4,LS Fork1,Axis_rot_1,rot_1,continuous,0,0,"0,20136","1,5708",0,"-3,1416",Base_link,0,1,0,,,,,,,,,,,,
|
||||
Link_1,"0,00186712264682618","-0,000412152188777493","0,0516389446895802",0,0,0,"1,58688811563125","0,00315699373090848","2,84713820858521E-05","7,01601261191599E-05","0,00343729241263711","-0,000101485203138906","0,00125534890134053",0,0,0,0,0,0,package://arm_assembly_/meshes/Link_1.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Link_1.STL,,assemb_link_220316-1,Origin_rot_2,Axis_rot_2,rot_2,continuous,"0,11","0,115",0,"1,5708","-1,5708",0,Fork_1,1,0,0,0,0,-31416,15708,,,,,,,,
|
||||
Fork_2,"0,0472051139085306","0,00208890925682994","0,0557265410642579",0,0,0,"1,12472202892859","0,00367804533572757","1,04277925521839E-05","-0,00149971410403071","0,00415208849477533","-5,67049464176431E-06","0,00418323534556488",0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_2.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_2.STL,,asm_fork_220606-1,LS Fork 2,Axis_rot_3,rot_3,continuous,"0,001",0,"0,156",0,0,"1,5708",Link_1,0,0,1,,,,,,,,,,,,
|
||||
Link_2,"-0,000432876513268311","0,000412152066707444","-0,0516389448183723",0,0,0,"1,58688811045174","0,00315699369986102","-2,84713874261321E-05","-7,01601002852263E-05","0,00343729240547401","-0,000101485187086936","0,00125534888404072",0,0,0,0,0,0,package://arm_assembly_/meshes/Link_2.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Link_2.STL,,assemb_link_220316-2,Origin_rot_4,Axis_rot_4,rot_4,continuous,"0,11",0,"0,115","3,1416",0,"-1,5708",Fork_2,1,0,0,0,0,-31416,15708,,,,,,,,
|
||||
Fork_3,"0,0472051139085305","0,00208890925682995","0,0557265410642568",0,0,0,"1,12472202892859","0,00367804533572756","1,04277925521852E-05","-0,00149971410403071","0,00415208849477532","-5,67049464176495E-06","0,00418323534556488",0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_3.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Fork_3.STL,,asm_fork_220606-2,LS Fork 3,Axis_rot_5,rot_5,continuous,"-0,00130000000000235",0,"-0,156000000000001","-3,14159265358979",0,"-1,5707963267949",Link_2,0,0,1,,,,,,,,,,,,
|
||||
Dock_Link,"-9,75315397450105E-06","-0,000888494418853673","0,0342332199538132",0,0,0,"1,26942368542281","0,00147695259043489","-2,66894744421543E-05","-4,40871314563024E-05","0,00135500487881815","-3,19001462977757E-05","0,000875828927068793",0,0,0,0,0,0,package://arm_assembly_/meshes/Dock_Link.STL,"0,752941176470588","0,752941176470588","0,752941176470588",1,0,0,0,0,0,0,package://arm_assembly_/meshes/Dock_Link.STL,,dokin_link_220706-1,Origin_rot_6,Ось1,rot_6,continuous,"0,11",0,"0,115",0,0,0,Fork_3,0,1,0,0,0,-31416,15708,,,,,,,,
|
|
|
@ -3,35 +3,35 @@
|
|||
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="arm_assembly_">
|
||||
name="rasmt">
|
||||
<link
|
||||
name="Base_link">
|
||||
name="Base_Link">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.000297 0.096472 -0.00036103"
|
||||
xyz="-0.000297002857922682 0.0964721185617698 -0.000361033370053684"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.8803" />
|
||||
value="1.88031044620482" />
|
||||
<inertia
|
||||
ixx="0.005033"
|
||||
ixy="0.00034382"
|
||||
ixz="-4.7499E-06"
|
||||
iyy="0.0033796"
|
||||
iyz="-2.3099E-05"
|
||||
izz="0.0040586" />
|
||||
ixx="0.00503302470272442"
|
||||
ixy="0.000343817346410954"
|
||||
ixz="-4.74990755448368E-06"
|
||||
iyy="0.00337962410057753"
|
||||
iyz="-2.3099255620051E-05"
|
||||
izz="0.00405858207282473" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
rpy="0 0 3.1416" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Base_link.STL" />
|
||||
filename="package://viewer/meshes/visual/Base_Link.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -40,7 +40,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Base_link.STL" />
|
||||
filename="package://viewer/meshes/collision/Base_Link.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -48,17 +48,17 @@
|
|||
name="Fork_1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0472051139085305 0.0557265410642573 -0.00208890925682975"
|
||||
xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.12472202892859" />
|
||||
<inertia
|
||||
ixx="0.00367804533572758"
|
||||
ixy="-0.00149971410403071"
|
||||
ixz="-1.04277925521891E-05"
|
||||
iyy="0.0041832353455649"
|
||||
iyz="5.67049464176682E-06"
|
||||
izz="0.00415208849477534" />
|
||||
ixy="1.04277925521833E-05"
|
||||
ixz="-0.00149971410403071"
|
||||
iyy="0.00415208849477534"
|
||||
iyz="-5.67049464176624E-06"
|
||||
izz="0.0041832353455649" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -66,7 +66,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_1.STL" />
|
||||
filename="package://viewer/meshes/visual/Fork_1.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -80,38 +80,43 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_1.STL" />
|
||||
filename="package://viewer/meshes/collision/Fork_1.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_1"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.20136"
|
||||
rpy="1.5708 0 -3.1416" />
|
||||
xyz="0 0 0.201360610569537"
|
||||
rpy="0 0 -3.1416" />
|
||||
<parent
|
||||
link="Base_link" />
|
||||
link="Base_Link" />
|
||||
<child
|
||||
link="Fork_1" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="-3.1416"
|
||||
upper="3.1416"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link_1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.00186712264682618 -0.000412152188777493 0.0516389446895802"
|
||||
xyz="0.00186712264682627 -0.000412152188777604 0.0516389446895805"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.58688811563125" />
|
||||
value="1.58688811563124" />
|
||||
<inertia
|
||||
ixx="0.00315699373090848"
|
||||
ixy="2.84713820858521E-05"
|
||||
ixz="7.01601261191599E-05"
|
||||
iyy="0.00343729241263711"
|
||||
iyz="-0.000101485203138906"
|
||||
izz="0.00125534890134053" />
|
||||
ixx="0.00315699373090845"
|
||||
ixy="2.84713820858537E-05"
|
||||
ixz="7.01601261191721E-05"
|
||||
iyy="0.00343729241263707"
|
||||
iyz="-0.000101485203138902"
|
||||
izz="0.00125534890134052" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -119,7 +124,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Link_1.STL" />
|
||||
filename="package://viewer/meshes/visual/Link_1.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -133,25 +138,25 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Link_1.STL" />
|
||||
filename="package://viewer/meshes/collision/Link_1.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_2"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0.11 0.115 0"
|
||||
rpy="1.5708 -1.5708 0" />
|
||||
xyz="0.11 0 0.115"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Fork_1" />
|
||||
<child
|
||||
link="Link_1" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-31416"
|
||||
upper="15708"
|
||||
lower="3.1415"
|
||||
upper="-1.5708"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
|
@ -159,16 +164,16 @@
|
|||
name="Fork_2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0472051139085306 0.00208890925682994 0.0557265410642579"
|
||||
xyz="0.0472051139085305 0.00208890925682995 0.0557265410642578"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.12472202892859" />
|
||||
<inertia
|
||||
ixx="0.00367804533572757"
|
||||
ixy="1.04277925521839E-05"
|
||||
ixy="1.04277925521844E-05"
|
||||
ixz="-0.00149971410403071"
|
||||
iyy="0.00415208849477533"
|
||||
iyz="-5.67049464176431E-06"
|
||||
iyz="-5.67049464176452E-06"
|
||||
izz="0.00418323534556488" />
|
||||
</inertial>
|
||||
<visual>
|
||||
|
@ -177,7 +182,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_2.STL" />
|
||||
filename="package://viewer/meshes/visual/Fork_2.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -191,37 +196,42 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_2.STL" />
|
||||
filename="package://viewer/meshes/collision/Fork_2.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_3"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0.001 0 0.156"
|
||||
rpy="0 0 1.5708" />
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link_1" />
|
||||
<child
|
||||
link="Fork_2" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="-3.1416"
|
||||
upper="3.1416"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link_2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.000432876513268311 0.000412152066707444 -0.0516389448183723"
|
||||
xyz="-0.000432876513268232 0.000412152066707638 -0.0516389448183734"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.58688811045174" />
|
||||
value="1.58688811045173" />
|
||||
<inertia
|
||||
ixx="0.00315699369986102"
|
||||
ixy="-2.84713874261321E-05"
|
||||
ixz="-7.01601002852263E-05"
|
||||
iyy="0.00343729240547401"
|
||||
iyz="-0.000101485187086936"
|
||||
ixx="0.003156993699861"
|
||||
ixy="-2.84713874261319E-05"
|
||||
ixz="-7.01601002852382E-05"
|
||||
iyy="0.00343729240547398"
|
||||
iyz="-0.000101485187086937"
|
||||
izz="0.00125534888404072" />
|
||||
</inertial>
|
||||
<visual>
|
||||
|
@ -230,7 +240,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Link_2.STL" />
|
||||
filename="package://viewer/meshes/visual/Link_2.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -244,25 +254,25 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Link_2.STL" />
|
||||
filename="package://viewer/meshes/collision/Link_2.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_4"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0.11 0 0.115"
|
||||
rpy="3.1416 0 -1.5708" />
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Fork_2" />
|
||||
<child
|
||||
link="Link_2" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-31416"
|
||||
upper="15708"
|
||||
lower="3.1416"
|
||||
upper="-1.5708"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
|
@ -270,16 +280,16 @@
|
|||
name="Fork_3">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0472051139085305 0.00208890925682995 0.0557265410642568"
|
||||
xyz="0.0472051139085305 0.00208890925682995 0.0557265410642577"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.12472202892859" />
|
||||
<inertia
|
||||
ixx="0.00367804533572756"
|
||||
ixy="1.04277925521852E-05"
|
||||
ixx="0.00367804533572757"
|
||||
ixy="1.04277925521856E-05"
|
||||
ixz="-0.00149971410403071"
|
||||
iyy="0.00415208849477532"
|
||||
iyz="-5.67049464176495E-06"
|
||||
iyz="-5.67049464176534E-06"
|
||||
izz="0.00418323534556488" />
|
||||
</inertial>
|
||||
<visual>
|
||||
|
@ -288,7 +298,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_3.STL" />
|
||||
filename="package://viewer/meshes/visual/Fork_3.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -302,46 +312,51 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Fork_3.STL" />
|
||||
filename="package://viewer/meshes/collision/Fork_3.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_5"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="-0.00130000000000235 0 -0.156000000000001"
|
||||
rpy="-3.14159265358979 0 -1.5707963267949" />
|
||||
xyz="-0.000 0 0.156"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link_2" />
|
||||
<child
|
||||
link="Fork_3" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="-3.1416"
|
||||
upper="3.1416"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Dock_Link">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-9.75315397450105E-06 -0.000888494418853673 0.0342332199538132"
|
||||
xyz="-9.7531539777207E-06 -0.000888494418875867 0.0342332199538358"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.26942368542281" />
|
||||
value="1.26942368542312" />
|
||||
<inertia
|
||||
ixx="0.00147695259043489"
|
||||
ixy="-2.66894744421543E-05"
|
||||
ixz="-4.40871314563024E-05"
|
||||
iyy="0.00135500487881815"
|
||||
iyz="-3.19001462977757E-05"
|
||||
izz="0.000875828927068793" />
|
||||
ixx="0.00147695259043549"
|
||||
ixy="-2.66894744420299E-05"
|
||||
ixz="-4.40871314563273E-05"
|
||||
iyy="0.00135500487881796"
|
||||
iyz="-3.19001462979333E-05"
|
||||
izz="0.00087582892706912" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
rpy="0 0 1.5708" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Dock_Link.STL" />
|
||||
filename="package://viewer/meshes/visual/Dock_Link.dae" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
|
@ -355,13 +370,13 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://arm_assembly_/meshes/Dock_Link.STL" />
|
||||
filename="package://viewer/meshes/collision/Dock_Link.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="rot_6"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0.11 0 0.115"
|
||||
rpy="0 0 0" />
|
||||
|
@ -372,9 +387,26 @@
|
|||
<axis
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-31416"
|
||||
upper="15708"
|
||||
lower="3.1416"
|
||||
upper="-1.5708"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
|
||||
</joint>
|
||||
<link
|
||||
name="Tool_Base"/>
|
||||
<joint
|
||||
name="tool"
|
||||
type="fixed">
|
||||
<origin
|
||||
xyz="0 0 0.115"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Dock_Link" />
|
||||
<child
|
||||
link="Tool_Base" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
</joint>
|
||||
</robot>
|