🔧 update urdf and add tool0 to chain
This commit is contained in:
parent
4fe0324b25
commit
dfaea654f1
13 changed files with 302 additions and 239 deletions
BIN
rasms_description/meshes/base.stl
Executable file → Normal file
BIN
rasms_description/meshes/base.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link1.stl
Executable file → Normal file
BIN
rasms_description/meshes/link1.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link2.stl
Executable file → Normal file
BIN
rasms_description/meshes/link2.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link3.stl
Executable file → Normal file
BIN
rasms_description/meshes/link3.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link4.stl
Executable file → Normal file
BIN
rasms_description/meshes/link4.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link5.stl
Executable file → Normal file
BIN
rasms_description/meshes/link5.stl
Executable file → Normal file
Binary file not shown.
BIN
rasms_description/meshes/link6.stl
Executable file → Normal file
BIN
rasms_description/meshes/link6.stl
Executable file → Normal file
Binary file not shown.
|
@ -7,7 +7,6 @@
|
|||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
|
||||
<parameters>$(find rasms_moveit_config)/config/rasms_controllers.yml</parameters>
|
||||
<robotNamespace>/rasms</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
|
|
|
@ -1,65 +1,24 @@
|
|||
<robot name="rasms">
|
||||
<link name="world"/>
|
||||
<joint name="to_world" type="fixed">
|
||||
<parent link="world"/>
|
||||
<child link="base"/>
|
||||
<origin xyz="0.0 0.0 0.07" rpy="0.0 0.0 0.0"/>
|
||||
</joint>
|
||||
<?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="rasms">
|
||||
<link
|
||||
name="base">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.000332122479320982 0.000107427994729828 -0.0364210136165633"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.31011976880718" />
|
||||
<inertia
|
||||
ixx="0.00259583556985636"
|
||||
ixy="9.78631121059142E-07"
|
||||
ixz="-1.47312310265428E-05"
|
||||
iyy="0.00238834687122552"
|
||||
iyz="5.81913913034168E-07"
|
||||
izz="0.00430679870377171" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/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://rasms_description/meshes/base.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link
|
||||
name="link1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.028753 0.080526 1.3501E-08"
|
||||
xyz="-0.00033212 0.00010743 -0.036421"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.52648" />
|
||||
value="1.3101" />
|
||||
<inertia
|
||||
ixx="0.00076496"
|
||||
ixy="-3.5256E-05"
|
||||
ixz="-2.8173E-10"
|
||||
iyy="0.00038929"
|
||||
iyz="1.9918E-09"
|
||||
izz="0.00075521" />
|
||||
ixx="0.0025958"
|
||||
ixy="9.7863E-07"
|
||||
ixz="-1.4731E-05"
|
||||
iyy="0.0023883"
|
||||
iyz="5.8191E-07"
|
||||
izz="0.0043068" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -67,10 +26,10 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link1.stl" />
|
||||
filename="package://rasms_description/meshes/base.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
|
@ -81,38 +40,25 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link1.stl" />
|
||||
filename="package://rasms_description/meshes/base.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint1"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="1.5708 0 -1.5708" />
|
||||
<parent
|
||||
link="base" />
|
||||
<child
|
||||
link="link1" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link2">
|
||||
name="link1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0098423932944443 0.025631709550142 2.62062855886029E-08"
|
||||
xyz="0.080526 -0.028752 -0.00018483"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.466449031624498" />
|
||||
value="0.52648" />
|
||||
<inertia
|
||||
ixx="0.000250149264856934"
|
||||
ixy="-6.39625267943634E-06"
|
||||
ixz="1.16240576365026E-09"
|
||||
iyy="0.000302356392836182"
|
||||
iyz="-5.72107071817652E-10"
|
||||
izz="0.000264859050215469" />
|
||||
ixx="0.00038929"
|
||||
ixy="3.5255E-05"
|
||||
ixz="2.2864E-07"
|
||||
iyy="0.00076496"
|
||||
iyz="6.2982E-08"
|
||||
izz="0.00075521" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -120,12 +66,12 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link2.stl" />
|
||||
filename="package://rasms_description/meshes/link1.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -134,7 +80,65 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link2.stl" />
|
||||
filename="package://rasms_description/meshes/link1.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="joint1"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="3.1352 -1.5708 0" />
|
||||
<parent
|
||||
link="base" />
|
||||
<child
|
||||
link="link1" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-3.1416"
|
||||
upper="3.1416"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.025632 0.0098422 6.3301E-05"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.46645" />
|
||||
<inertia
|
||||
ixx="0.00030236"
|
||||
ixy="6.3961E-06"
|
||||
ixz="4.0548E-08"
|
||||
iyy="0.00025015"
|
||||
iyz="-9.5727E-08"
|
||||
izz="0.00026486" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link2.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="rasms_color">
|
||||
<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://rasms_description/meshes/link2.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -142,30 +146,35 @@
|
|||
name="joint2"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.14172 0"
|
||||
xyz="0.14172 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link1" />
|
||||
<child
|
||||
link="link2" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link3">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0215100033761789 0.0694423986454957 3.93278649368959E-08"
|
||||
xyz="0.069442 -0.021508 -0.00029297"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.70816935413754" />
|
||||
value="0.70817" />
|
||||
<inertia
|
||||
ixx="0.000864850509477081"
|
||||
ixy="-3.62319530566251E-05"
|
||||
ixz="-2.95541145601842E-10"
|
||||
iyy="0.000482143975333292"
|
||||
iyz="2.00353934934295E-09"
|
||||
izz="0.000860394915615017" />
|
||||
ixx="0.00048214"
|
||||
ixy="3.6229E-05"
|
||||
ixz="4.9555E-07"
|
||||
iyy="0.00086485"
|
||||
iyz="6.0984E-08"
|
||||
izz="0.0008604" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -173,12 +182,12 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link3.stl" />
|
||||
filename="package://rasms_description/meshes/link3.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -187,7 +196,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link3.stl" />
|
||||
filename="package://rasms_description/meshes/link3.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -195,30 +204,35 @@
|
|||
name="joint3"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.081346 0"
|
||||
rpy="0 0.0071935 0" />
|
||||
xyz="0.081346 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link2" />
|
||||
<child
|
||||
link="link3" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link4">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0098423941326931 0.025631710847922 2.62314079923008E-08"
|
||||
xyz="0.025632 0.0098415 0.0001341"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.466449036998311" />
|
||||
value="0.46645" />
|
||||
<inertia
|
||||
ixx="0.0002501492525602"
|
||||
ixy="-6.39624584934821E-06"
|
||||
ixz="1.15937712750973E-09"
|
||||
iyy="0.000302356392948396"
|
||||
iyz="-5.70585180406975E-10"
|
||||
izz="0.000264859056361031" />
|
||||
ixx="0.00030236"
|
||||
ixy="6.3957E-06"
|
||||
ixz="8.6559E-08"
|
||||
iyy="0.00025015"
|
||||
iyz="-2.0152E-07"
|
||||
izz="0.00026486" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -226,12 +240,12 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link4.stl" />
|
||||
filename="package://rasms_description/meshes/link4.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -240,7 +254,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link4.stl" />
|
||||
filename="package://rasms_description/meshes/link4.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -248,30 +262,35 @@
|
|||
name="joint4"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.14438 0"
|
||||
xyz="0.14438 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link3" />
|
||||
<child
|
||||
link="link4" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link5">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0215100033039704 0.0694423990612557 3.93278667377771E-08"
|
||||
xyz="0.069442 -0.021508 -0.00029297"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.708169356775496" />
|
||||
value="0.70817" />
|
||||
<inertia
|
||||
ixx="0.000864850515095"
|
||||
ixy="-3.6231953093431E-05"
|
||||
ixz="-2.95541136548844E-10"
|
||||
iyy="0.000482143976309882"
|
||||
iyz="2.00353938873391E-09"
|
||||
izz="0.000860394921240315" />
|
||||
ixx="0.00048214"
|
||||
ixy="3.6229E-05"
|
||||
ixz="4.9555E-07"
|
||||
iyy="0.00086485"
|
||||
iyz="6.0984E-08"
|
||||
izz="0.0008604" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -279,12 +298,12 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link5.stl" />
|
||||
filename="package://rasms_description/meshes/link5.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -293,7 +312,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link5.stl" />
|
||||
filename="package://rasms_description/meshes/link5.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -301,30 +320,35 @@
|
|||
name="joint5"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.081346 0"
|
||||
xyz="0.081346 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link4" />
|
||||
<child
|
||||
link="link5" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link6">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0107961703559938 0.0337046197725978 6.41961769822694E-06"
|
||||
xyz="0.033705 0.010795 0.00015348"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.599356299495803" />
|
||||
value="0.59936" />
|
||||
<inertia
|
||||
ixx="0.000286310483854348"
|
||||
ixy="-5.79903953240378E-06"
|
||||
ixz="6.26853068396246E-08"
|
||||
iyy="0.000358508548445319"
|
||||
iyz="-4.97585335654749E-10"
|
||||
izz="0.000295138763544911" />
|
||||
ixx="0.00035851"
|
||||
ixy="5.7985E-06"
|
||||
ixz="7.8497E-08"
|
||||
iyy="0.00028631"
|
||||
iyz="-1.8291E-07"
|
||||
izz="0.00029514" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -332,12 +356,12 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link6.stl" />
|
||||
filename="package://rasms_description/meshes/link6.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -346,7 +370,7 @@
|
|||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="package://rasms_description/meshes/link6.stl" />
|
||||
filename="package://rasms_description/meshes/link6.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
@ -354,13 +378,18 @@
|
|||
name="joint6"
|
||||
type="continuous">
|
||||
<origin
|
||||
xyz="0 0.14438 0"
|
||||
xyz="0.14438 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link5" />
|
||||
<child
|
||||
link="link6" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
</robot>
|
|
@ -12,19 +12,19 @@
|
|||
</joint>
|
||||
<link
|
||||
name="base">
|
||||
<inertial>
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.000332122479320982 0.000107427994729828 -0.0364210136165633"
|
||||
xyz="-0.00033212 0.00010743 -0.036421"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="1.31011976880718" />
|
||||
value="1.3101" />
|
||||
<inertia
|
||||
ixx="0.00259583556985636"
|
||||
ixy="9.78631121059142E-07"
|
||||
ixz="-1.47312310265428E-05"
|
||||
iyy="0.00238834687122552"
|
||||
iyz="5.81913913034168E-07"
|
||||
izz="0.00430679870377171" />
|
||||
ixx="0.0025958"
|
||||
ixy="9.7863E-07"
|
||||
ixz="-1.4731E-05"
|
||||
iyy="0.0023883"
|
||||
iyz="5.8191E-07"
|
||||
izz="0.0043068" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -35,9 +35,9 @@
|
|||
filename="package://rasms_description/meshes/base.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -54,16 +54,16 @@
|
|||
name="link1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.028753 0.080526 1.3501E-08"
|
||||
xyz="0.080526 -0.028752 -0.00018483"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.52648" />
|
||||
<inertia
|
||||
ixx="0.00076496"
|
||||
ixy="-3.5256E-05"
|
||||
ixz="-2.8173E-10"
|
||||
iyy="0.00038929"
|
||||
iyz="1.9918E-09"
|
||||
ixx="0.00038929"
|
||||
ixy="3.5255E-05"
|
||||
ixz="2.2864E-07"
|
||||
iyy="0.00076496"
|
||||
iyz="6.2982E-08"
|
||||
izz="0.00075521" />
|
||||
</inertial>
|
||||
<visual>
|
||||
|
@ -75,7 +75,7 @@
|
|||
filename="package://rasms_description/meshes/link1.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
|
@ -92,32 +92,37 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint1"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="1.5708 0 -1.5708" />
|
||||
rpy="0 -1.5708 0" />
|
||||
<parent
|
||||
link="base" />
|
||||
<child
|
||||
link="link1" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-3.1416"
|
||||
upper="3.1416"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0098423932944443 0.025631709550142 2.62062855886029E-08"
|
||||
xyz="0.025632 0.0098422 6.3301E-05"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.466449031624498" />
|
||||
value="0.46645" />
|
||||
<inertia
|
||||
ixx="0.000250149264856934"
|
||||
ixy="-6.39625267943634E-06"
|
||||
ixz="1.16240576365026E-09"
|
||||
iyy="0.000302356392836182"
|
||||
iyz="-5.72107071817652E-10"
|
||||
izz="0.000264859050215469" />
|
||||
ixx="0.00030236"
|
||||
ixy="6.3961E-06"
|
||||
ixz="4.0548E-08"
|
||||
iyy="0.00025015"
|
||||
iyz="-9.5727E-08"
|
||||
izz="0.00026486" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -128,9 +133,9 @@
|
|||
filename="package://rasms_description/meshes/link2.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -145,32 +150,37 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint2"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0.14172 0"
|
||||
xyz="0.14172 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link1" />
|
||||
<child
|
||||
link="link2" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link3">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0215100033761789 0.0694423986454957 3.93278649368959E-08"
|
||||
xyz="0.069442 -0.021508 -0.00029297"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.70816935413754" />
|
||||
value="0.70817" />
|
||||
<inertia
|
||||
ixx="0.000864850509477081"
|
||||
ixy="-3.62319530566251E-05"
|
||||
ixz="-2.95541145601842E-10"
|
||||
iyy="0.000482143975333292"
|
||||
iyz="2.00353934934295E-09"
|
||||
izz="0.000860394915615017" />
|
||||
ixx="0.00048214"
|
||||
ixy="3.6229E-05"
|
||||
ixz="4.9555E-07"
|
||||
iyy="0.00086485"
|
||||
iyz="6.0984E-08"
|
||||
izz="0.0008604" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -181,9 +191,9 @@
|
|||
filename="package://rasms_description/meshes/link3.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -198,32 +208,37 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint3"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0.081346 0"
|
||||
rpy="0 0.0071935 0" />
|
||||
xyz="0.081346 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link2" />
|
||||
<child
|
||||
link="link3" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link4">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0098423941326931 0.025631710847922 2.62314079923008E-08"
|
||||
xyz="0.025632 0.0098415 0.0001341"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.466449036998311" />
|
||||
value="0.46645" />
|
||||
<inertia
|
||||
ixx="0.0002501492525602"
|
||||
ixy="-6.39624584934821E-06"
|
||||
ixz="1.15937712750973E-09"
|
||||
iyy="0.000302356392948396"
|
||||
iyz="-5.70585180406975E-10"
|
||||
izz="0.000264859056361031" />
|
||||
ixx="0.00030236"
|
||||
ixy="6.3957E-06"
|
||||
ixz="8.6559E-08"
|
||||
iyy="0.00025015"
|
||||
iyz="-2.0152E-07"
|
||||
izz="0.00026486" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -234,9 +249,9 @@
|
|||
filename="package://rasms_description/meshes/link4.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -251,32 +266,37 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint4"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0.14438 0"
|
||||
xyz="0.14438 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link3" />
|
||||
<child
|
||||
link="link4" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link5">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0215100033039704 0.0694423990612557 3.93278667377771E-08"
|
||||
xyz="0.069442 -0.021508 -0.00029297"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.708169356775496" />
|
||||
value="0.70817" />
|
||||
<inertia
|
||||
ixx="0.000864850515095"
|
||||
ixy="-3.6231953093431E-05"
|
||||
ixz="-2.95541136548844E-10"
|
||||
iyy="0.000482143976309882"
|
||||
iyz="2.00353938873391E-09"
|
||||
izz="0.000860394921240315" />
|
||||
ixx="0.00048214"
|
||||
ixy="3.6229E-05"
|
||||
ixz="4.9555E-07"
|
||||
iyy="0.00086485"
|
||||
iyz="6.0984E-08"
|
||||
izz="0.0008604" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -287,9 +307,9 @@
|
|||
filename="package://rasms_description/meshes/link5.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -304,32 +324,37 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint5"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0.081346 0"
|
||||
xyz="0.081346 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link4" />
|
||||
<child
|
||||
link="link5" />
|
||||
<axis
|
||||
xyz="0 1 0" />
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link
|
||||
name="link6">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0107961703559938 0.0337046197725978 6.41961769822694E-06"
|
||||
xyz="0.033705 0.010795 0.00015348"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.599356299495803" />
|
||||
value="0.59936" />
|
||||
<inertia
|
||||
ixx="0.000286310483854348"
|
||||
ixy="-5.79903953240378E-06"
|
||||
ixz="6.26853068396246E-08"
|
||||
iyy="0.000358508548445319"
|
||||
iyz="-4.97585335654749E-10"
|
||||
izz="0.000295138763544911" />
|
||||
ixx="0.00035851"
|
||||
ixy="5.7985E-06"
|
||||
ixz="7.8497E-08"
|
||||
iyy="0.00028631"
|
||||
iyz="-1.8291E-07"
|
||||
izz="0.00029514" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
|
@ -340,9 +365,9 @@
|
|||
filename="package://rasms_description/meshes/link6.stl" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
name="rasms_color">
|
||||
<color
|
||||
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
||||
rgba="0.79216 0.81961 0.93333 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
@ -357,18 +382,28 @@
|
|||
</link>
|
||||
<joint
|
||||
name="joint6"
|
||||
type="continuous">
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0.14438 0"
|
||||
xyz="0.14438 0 0"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="link5" />
|
||||
<child
|
||||
link="link6" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
xyz="0 1 0" />
|
||||
<limit
|
||||
lower="-2.0944"
|
||||
upper="2.0944"
|
||||
effort="0"
|
||||
velocity="0" />
|
||||
</joint>
|
||||
<link name="tool0"/>
|
||||
<joint name="to_tool0" type="fixed">
|
||||
<parent link="link6"/>
|
||||
<child link="tool0"/>
|
||||
<origin xyz="0.101 0 0" rpy="0 1.5708 0"/>
|
||||
</joint>
|
||||
|
||||
<xacro:rasms_hi/>
|
||||
<xacro:rasms_gazebo/>
|
||||
</robot>
|
|
@ -213,7 +213,7 @@ int main(int argc, char** argv)
|
|||
// Let's specify a path constraint and a pose goal for our group.
|
||||
// First define the path constraint.
|
||||
moveit_msgs::msg::OrientationConstraint ocm;
|
||||
ocm.link_name = "link6";
|
||||
ocm.link_name = "tool0";
|
||||
ocm.header.frame_id = "base";
|
||||
ocm.orientation.w = 1.0;
|
||||
ocm.absolute_x_axis_tolerance = 0.1;
|
||||
|
|
|
@ -7,7 +7,7 @@ Panels:
|
|||
- /Global Options1
|
||||
- /Status1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 197
|
||||
Tree Height: 356
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
|
@ -385,7 +385,7 @@ Visualization Manager:
|
|||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 3.8008623123168945
|
||||
Distance: 2.561343193054199
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
|
@ -400,10 +400,10 @@ Visualization Manager:
|
|||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.72039794921875
|
||||
Pitch: 0.6653979420661926
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.2953982949256897
|
||||
Yaw: 0.26539817452430725
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
|
@ -415,7 +415,7 @@ Window Geometry:
|
|||
collapsed: false
|
||||
MotionPlanning - Trajectory Slider:
|
||||
collapsed: false
|
||||
QMainWindow State: 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
|
||||
QMainWindow State: 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
|
||||
RvizVisualToolsGui:
|
||||
collapsed: false
|
||||
Selection:
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
|
||||
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
|
||||
<group name="rasms_arm_group">
|
||||
<chain base_link="base" tip_link="link6"/>
|
||||
<chain base_link="base" tip_link="tool0"/>
|
||||
</group>
|
||||
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
|
||||
<group_state name="zero_pose" group="rasms_arm_group">
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue