873 lines
36 KiB
XML
873 lines
36 KiB
XML
<?xml version="1.0" ?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from openarm_bimanual.urdf.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="openarm_bimanual">
|
|
<material name="gray">
|
|
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
|
|
</material>
|
|
<material name="dark_gray">
|
|
<color rgba="0.19607843137254902 0.19607843137254902 0.19607843137254902 1.0"/>
|
|
</material>
|
|
<link name="pedestal_link">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_bimanual_description/meshes/pedestal_link.stl"/>
|
|
</geometry>
|
|
<material name="gray">
|
|
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.489"/>
|
|
<geometry>
|
|
<box size="0.18 0.06 0.978000000000004"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="4.850309883435878"/>
|
|
<origin rpy="0 0 0" xyz="0.0 -0.0180451 0.410247"/>
|
|
<inertia ixx="0.6232810322991779" ixy="7.916644206828546e-12" ixz="-1.094192214704477e-11" iyy="0.6253514495087933" iyz="-0.03342233248166168" izz="0.02000994027356939"/>
|
|
</inertial>
|
|
</link>
|
|
<material name="aluminum">
|
|
<color rgba="0.5 0.5 0.5 1"/>
|
|
</material>
|
|
<material name="plastic">
|
|
<color rgba="0.1 0.1 0.1 1"/>
|
|
</material>
|
|
<!-- camera body, with origin at bottom screw mount -->
|
|
<joint name="camera_joint" type="fixed">
|
|
<origin rpy="0.0 1.3962634015954636 -1.5707963267948966" xyz="0.0 -0.025 0.995216"/>
|
|
<parent link="pedestal_link"/>
|
|
<child link="camera_bottom_screw_frame"/>
|
|
</joint>
|
|
<link name="camera_bottom_screw_frame"/>
|
|
<joint name="camera_link_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0.010600000000000002 0.0175 0.0125"/>
|
|
<parent link="camera_bottom_screw_frame"/>
|
|
<child link="camera_link"/>
|
|
</joint>
|
|
<link name="camera_link">
|
|
<visual>
|
|
<!-- the mesh origin is at front plate in between the two infrared camera axes -->
|
|
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0.0043 -0.0175 0"/>
|
|
<geometry>
|
|
<mesh filename="file:///opt/ros/humble/share/realsense2_description/meshes/d435.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 -0.0175 0"/>
|
|
<geometry>
|
|
<box size="0.02505 0.09 0.025"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<!-- The following are not reliable values, and should not be used for modeling -->
|
|
<mass value="0.072"/>
|
|
<origin xyz="0 0 0"/>
|
|
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- camera depth joints and links -->
|
|
<joint name="camera_depth_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_depth_frame"/>
|
|
</joint>
|
|
<link name="camera_depth_frame"/>
|
|
<joint name="camera_depth_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_depth_frame"/>
|
|
<child link="camera_depth_optical_frame"/>
|
|
</joint>
|
|
<link name="camera_depth_optical_frame"/>
|
|
<!-- camera left IR joints and links -->
|
|
<joint name="camera_infra1_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0.0 0"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_infra1_frame"/>
|
|
</joint>
|
|
<link name="camera_infra1_frame"/>
|
|
<joint name="camera_infra1_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_infra1_frame"/>
|
|
<child link="camera_infra1_optical_frame"/>
|
|
</joint>
|
|
<link name="camera_infra1_optical_frame"/>
|
|
<!-- camera right IR joints and links -->
|
|
<joint name="camera_infra2_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 -0.05 0"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_infra2_frame"/>
|
|
</joint>
|
|
<link name="camera_infra2_frame"/>
|
|
<joint name="camera_infra2_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_infra2_frame"/>
|
|
<child link="camera_infra2_optical_frame"/>
|
|
</joint>
|
|
<link name="camera_infra2_optical_frame"/>
|
|
<!-- camera color joints and links -->
|
|
<joint name="camera_color_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0.015 0"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_color_frame"/>
|
|
</joint>
|
|
<link name="camera_color_frame"/>
|
|
<joint name="camera_color_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_color_frame"/>
|
|
<child link="camera_color_optical_frame"/>
|
|
</joint>
|
|
<link name="camera_color_optical_frame"/>
|
|
<link name="camera_accel_frame"/>
|
|
<link name="camera_accel_optical_frame"/>
|
|
<link name="camera_gyro_frame"/>
|
|
<link name="camera_gyro_optical_frame"/>
|
|
<joint name="camera_accel_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_accel_frame"/>
|
|
</joint>
|
|
<joint name="camera_accel_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_accel_frame"/>
|
|
<child link="camera_accel_optical_frame"/>
|
|
</joint>
|
|
<joint name="camera_gyro_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
|
|
<parent link="camera_link"/>
|
|
<child link="camera_gyro_frame"/>
|
|
</joint>
|
|
<joint name="camera_gyro_optical_joint" type="fixed">
|
|
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
|
|
<parent link="camera_gyro_frame"/>
|
|
<child link="camera_gyro_optical_frame"/>
|
|
</joint>
|
|
<link name="world"/>
|
|
<joint name="dummy_joint" type="fixed">
|
|
<parent link="world"/>
|
|
<child link="pedestal_link"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
|
|
</joint>
|
|
<!-- side right, left -->
|
|
<!-- recommended prefixes left_, right_, etc. -->
|
|
<!-- zero_pos up, arm -->
|
|
<ros2_control name="right_OpenArmHW" type="system">
|
|
<hardware>
|
|
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
|
|
<!-- <plugin>mock_components/GenericSystem</plugin> -->
|
|
<plugin>openarm_hardware/OpenArmHW</plugin>
|
|
<param name="prefix">right_</param>
|
|
<param name="can_device">can0</param>
|
|
</hardware>
|
|
<joint name="right_rev1">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev2">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev3">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev4">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev5">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev6">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_rev7">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="right_left_pris1">
|
|
<command_interface name="position"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
</joint>
|
|
<!-- <joint name="${prefix}right_pris2">
|
|
<state_interface name="position">
|
|
<param name="initial_value">${initial_positions['right_pris2']}</param>
|
|
</state_interface>
|
|
</joint> -->
|
|
</ros2_control>
|
|
<link name="right_dummy_link"/>
|
|
<joint name="right_dummy_joint" type="fixed">
|
|
<parent link="right_dummy_link"/>
|
|
<child link="right_link1"/>
|
|
</joint>
|
|
<link name="right_link1">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link1.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0289"/>
|
|
<geometry>
|
|
<box size="0.11 0.073 0.0592"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.5769283920617254"/>
|
|
<origin rpy="0 0 0" xyz="0.0 2.52845e-05 0.0229621"/>
|
|
<inertia ixx="0.00034035167574060775" ixy="-2.623557985991217e-18" ixz="-6.093726095527621e-18" iyy="0.0004300058300010205" iyz="-5.09829482074806e-07" izz="0.0004802171432001996"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link2">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link2.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0371236"/>
|
|
<geometry>
|
|
<box size="0.0590000000149012 0.08200000000000002 0.0742471498637348"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.16257504134917358"/>
|
|
<origin rpy="0 0 0" xyz="-0.000225878 -0.00183836 0.0278368"/>
|
|
<inertia ixx="0.00023903110213294374" ixy="-7.551692921096027e-08" ixz="-1.1282723362433474e-06" iyy="0.00010490798314778774" iyz="5.9079627839725245e-06" izz="0.00019737368685935776"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link3">
|
|
<visual>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link3.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="-0.0164466 -0.00045542 0.02975"/>
|
|
<geometry>
|
|
<box size="0.08989101803441879 0.06999999999999983 0.05903276947803012"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.4201676469910031"/>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="-0.00688022 0.0 0.0282752"/>
|
|
<inertia ixx="0.00020256001126230057" ixy="6.004247875311213e-06" ixz="1.3304903057525575e-06" iyy="0.0002970624991387495" iyz="5.980157765704868e-07" izz="0.00032889994351244413"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link4">
|
|
<visual>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link4.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="0.000266276 -0.0125642 -0.132604"/>
|
|
<geometry>
|
|
<box size="0.27584673777150337 0.08211429171582063 0.07186573179325861"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.819475539373447"/>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="0.000781326 -0.0019461 -0.132411"/>
|
|
<inertia ixx="0.00044078452033976287" ixy="6.020023694043618e-05" ixz="0.00014637459261941218" iyy="0.009208791480530413" iyz="1.5469710436444469e-06" izz="0.009170539316023695"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link5">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link5.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182894316818 0" xyz="-0.0542814 0.00265291 -0.0302022"/>
|
|
<geometry>
|
|
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.4086748254352304"/>
|
|
<origin rpy="0 -0.008758182894316905 0" xyz="-0.0831891 0.00251789 -0.0290107"/>
|
|
<inertia ixx="0.00031417157425298747" ixy="-1.1391566029536723e-05" ixz="-1.883474090056124e-05" iyy="0.001221711435313989" iyz="1.46725418421127e-06" izz="0.0010755135067660488"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link6">
|
|
<visual>
|
|
<origin rpy="-2.1276679791326423 -1.5542266826921929 0" xyz="-0.0485412 -0.0860404 0.437784"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link6_rightarm.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00260794 -0.00312921 -0.0652641"/>
|
|
<geometry>
|
|
<box size="0.13114353004704765 0.05953478325301745 0.08817196195081879"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.3448471958049249"/>
|
|
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00898536 -0.0135065 -0.0438611"/>
|
|
<inertia ixx="0.00019355980999748924" ixy="-1.0061665815148114e-06" ixz="-3.9096495715032716e-05" iyy="0.0003486912031865755" iyz="6.088060315273385e-06" izz="0.00028774975153756256"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link7">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link7_rightarm.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182894511114 0" xyz="-0.000318103 0.0022839 0.0340014"/>
|
|
<geometry>
|
|
<box size="0.058327402175132874 0.04432916698753661 0.08267601622411752"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.2782138078738053"/>
|
|
<origin rpy="0 -0.008758182894511043 0" xyz="5.99432e-05 0.0041433 0.0354274"/>
|
|
<inertia ixx="0.00010424153315648891" ixy="2.735265831785291e-07" ixz="-1.0662322382945994e-07" iyy="0.00012313550743283462" iyz="-8.604996754782856e-08" izz="9.221319958512582e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link8">
|
|
<visual>
|
|
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link8.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.042694 -0.000543176 0.0110286"/>
|
|
<geometry>
|
|
<box size="0.13038799671743653 0.05180887692688926 0.1601236763440867"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.31261452743802165"/>
|
|
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.0607602 -0.000341696 0.00876618"/>
|
|
<inertia ixx="0.00023465661366788053" ixy="7.609048882006294e-05" ixz="3.088694121124684e-07" iyy="0.0005065459365215377" iyz="1.9022818028658623e-07" izz="0.0003737029250058136"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_gripper_center"/>
|
|
<link name="right_link_left_jaw">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/left_jaw.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/left_jaw.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.04297897856394934"/>
|
|
<origin rpy="0 -0.008758182894469429 0" xyz="-0.0187138 0.00217075 0.0159499"/>
|
|
<inertia ixx="1.1771768742932353e-05" ixy="-2.389928166589898e-06" ixz="3.999292204534159e-06" iyy="2.3837354480794824e-05" iyz="3.494431877242991e-07" izz="3.0474590214086944e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="right_link_right_jaw">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/right_jaw.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/right_jaw.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.042981665301134515"/>
|
|
<origin rpy="0 -0.00875818289800148 0" xyz="-0.0187844 -0.00272415 -0.0159503"/>
|
|
<inertia ixx="1.1561293087621594e-05" ixy="2.537718468008212e-06" ixz="-3.6591812257702003e-06" iyy="2.370165527871047e-05" iyz="4.848038235889027e-07" izz="3.039652946542647e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="right_rev1" type="revolute">
|
|
<parent link="right_link1"/>
|
|
<child link="right_link2"/>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.05325"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev2" type="revolute">
|
|
<parent link="right_link2"/>
|
|
<child link="right_link3"/>
|
|
<origin rpy="-1.5707963267948968 0.0 0.0" xyz="0.0 -0.02975 0.04475"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="0" upper="3.141592653589793" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev3" type="revolute">
|
|
<parent link="right_link3"/>
|
|
<child link="right_link4"/>
|
|
<origin rpy="-1.5707963267949054 0 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.52359" upper="3.66519" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev4" type="revolute">
|
|
<parent link="right_link4"/>
|
|
<child link="right_link5"/>
|
|
<origin rpy="-0.20701608758495998 -1.5707963267948566 -2.937419385117548" xyz="0.0297547 0.0 -0.24175"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="-0.3490658503988659" upper="2.792526803190927" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev5" type="revolute">
|
|
<parent link="right_link5"/>
|
|
<child link="right_link6"/>
|
|
<origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev6" type="revolute">
|
|
<parent link="right_link6"/>
|
|
<child link="right_link7"/>
|
|
<origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_rev7" type="revolute">
|
|
<parent link="right_link7"/>
|
|
<child link="right_link8"/>
|
|
<origin rpy="-1.5707963267950005 -0.00875904933536772 -0.014066001454933467" xyz="-0.000217313 -0.0154485 0.0355"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.9599310885968813" upper="0.9599310885968813" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="right_left_pris1" type="prismatic">
|
|
<parent link="right_link8"/>
|
|
<child link="right_link_left_jaw"/>
|
|
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
|
|
</joint>
|
|
<joint name="right_right_pris2" type="prismatic">
|
|
<parent link="right_link8"/>
|
|
<child link="right_link_right_jaw"/>
|
|
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
|
|
<mimic joint="right_left_pris1" multiplier="-1.0" offset="0.0"/>
|
|
</joint>
|
|
<joint name="right_virtual_gripper_center" type="fixed">
|
|
<parent link="right_link8"/>
|
|
<child link="right_gripper_center"/>
|
|
<origin rpy="0 0 0" xyz="-0.13 0.00 0.0132053"/>
|
|
</joint>
|
|
<joint name="right_fixed1" type="fixed">
|
|
<parent link="pedestal_link"/>
|
|
<child link="right_dummy_link"/>
|
|
<origin rpy="6.160245846096606 -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/>
|
|
</joint>
|
|
<!-- side right, left -->
|
|
<!-- recommended prefixes left_, right_, etc. -->
|
|
<!-- zero_pos up, arm -->
|
|
<ros2_control name="left_OpenArmHW" type="system">
|
|
<hardware>
|
|
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
|
|
<!-- <plugin>mock_components/GenericSystem</plugin> -->
|
|
<plugin>openarm_hardware/OpenArmHW</plugin>
|
|
<param name="prefix">left_</param>
|
|
<param name="can_device">can1</param>
|
|
</hardware>
|
|
<joint name="left_rev1">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev2">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev3">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev4">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev5">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev6">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_rev7">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="left_left_pris1">
|
|
<command_interface name="position"/>
|
|
<state_interface name="position"/>
|
|
<state_interface name="velocity"/>
|
|
</joint>
|
|
<!-- <joint name="${prefix}right_pris2">
|
|
<state_interface name="position">
|
|
<param name="initial_value">${initial_positions['right_pris2']}</param>
|
|
</state_interface>
|
|
</joint> -->
|
|
</ros2_control>
|
|
<link name="left_dummy_link"/>
|
|
<joint name="left_dummy_joint" type="fixed">
|
|
<parent link="left_dummy_link"/>
|
|
<child link="left_link1"/>
|
|
</joint>
|
|
<link name="left_link1">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link1.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0289"/>
|
|
<geometry>
|
|
<box size="0.11 0.073 0.0592"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.5769283920617254"/>
|
|
<origin rpy="0 0 0" xyz="0.0 2.52845e-05 0.0229621"/>
|
|
<inertia ixx="0.00034035167574060775" ixy="-2.623557985991217e-18" ixz="-6.093726095527621e-18" iyy="0.0004300058300010205" iyz="-5.09829482074806e-07" izz="0.0004802171432001996"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link2">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link2.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0371236"/>
|
|
<geometry>
|
|
<box size="0.0590000000149012 0.08200000000000002 0.0742471498637348"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.16257504134917358"/>
|
|
<origin rpy="0 0 0" xyz="-0.000225878 -0.00183836 0.0278368"/>
|
|
<inertia ixx="0.00023903110213294374" ixy="-7.551692921096027e-08" ixz="-1.1282723362433474e-06" iyy="0.00010490798314778774" iyz="5.9079627839725245e-06" izz="0.00019737368685935776"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link3">
|
|
<visual>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link3.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="-0.0164466 -0.00045542 0.02975"/>
|
|
<geometry>
|
|
<box size="0.08989101803441879 0.06999999999999983 0.05903276947803012"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.4201676469910031"/>
|
|
<origin rpy="1.5707963267948966 0 0" xyz="-0.00688022 0.0 0.0282752"/>
|
|
<inertia ixx="0.00020256001126230057" ixy="6.004247875311213e-06" ixz="1.3304903057525575e-06" iyy="0.0002970624991387495" iyz="5.980157765704868e-07" izz="0.00032889994351244413"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link4">
|
|
<visual>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link4.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="0.000266276 -0.0125642 -0.132604"/>
|
|
<geometry>
|
|
<box size="0.27584673777150337 0.08211429171582063 0.07186573179325861"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.819475539373447"/>
|
|
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="0.000781326 -0.0019461 -0.132411"/>
|
|
<inertia ixx="0.00044078452033976287" ixy="6.020023694043618e-05" ixz="0.00014637459261941218" iyy="0.009208791480530413" iyz="1.5469710436444469e-06" izz="0.009170539316023695"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link5">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link5.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182894316818 0" xyz="-0.0542814 0.00265291 -0.0302022"/>
|
|
<geometry>
|
|
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.4086748254352304"/>
|
|
<origin rpy="0 -0.008758182894316905 0" xyz="-0.0831891 0.00251789 -0.0290107"/>
|
|
<inertia ixx="0.00031417157425298747" ixy="-1.1391566029536723e-05" ixz="-1.883474090056124e-05" iyy="0.001221711435313989" iyz="1.46725418421127e-06" izz="0.0010755135067660488"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link6">
|
|
<visual>
|
|
<origin rpy="5.269260632722435 1.5542266826921929 3.141592653589793" xyz="0.0605412 0.0878404 0.435484"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link6_leftarm.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00260794 -0.00312921 -0.0652641"/>
|
|
<geometry>
|
|
<box size="0.13114353004704765 0.05953478325301745 0.08817196195081879"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.3448471958049249"/>
|
|
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00898536 -0.0135065 -0.0438611"/>
|
|
<inertia ixx="0.00019355980999748924" ixy="-1.0061665815148114e-06" ixz="-3.9096495715032716e-05" iyy="0.0003486912031865755" iyz="6.088060315273385e-06" izz="0.00028774975153756256"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link7">
|
|
<visual>
|
|
<origin rpy="0 3.150350836484304 0" xyz="0.558839 -0.0034132900000000002 0.1341962"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link7_leftarm.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182894511114 0" xyz="-0.000318103 0.0022839 0.0340014"/>
|
|
<geometry>
|
|
<box size="0.058327402175132874 0.04432916698753661 0.08267601622411752"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.2782138078738053"/>
|
|
<origin rpy="0 -0.008758182894511043 0" xyz="5.99432e-05 0.0041433 0.0354274"/>
|
|
<inertia ixx="0.00010424153315648891" ixy="2.735265831785291e-07" ixz="-1.0662322382945994e-07" iyy="0.00012313550743283462" iyz="-8.604996754782856e-08" izz="9.221319958512582e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link8">
|
|
<visual>
|
|
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/link8.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.042694 -0.000543176 0.0110286"/>
|
|
<geometry>
|
|
<box size="0.13038799671743653 0.05180887692688926 0.1601236763440867"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.31261452743802165"/>
|
|
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.0607602 -0.000341696 0.00876618"/>
|
|
<inertia ixx="0.00023465661366788053" ixy="7.609048882006294e-05" ixz="3.088694121124684e-07" iyy="0.0005065459365215377" iyz="1.9022818028658623e-07" izz="0.0003737029250058136"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_gripper_center"/>
|
|
<link name="left_link_left_jaw">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/left_jaw.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/left_jaw.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.04297897856394934"/>
|
|
<origin rpy="0 -0.008758182894469429 0" xyz="-0.0187138 0.00217075 0.0159499"/>
|
|
<inertia ixx="1.1771768742932353e-05" ixy="-2.389928166589898e-06" ixz="3.999292204534159e-06" iyy="2.3837354480794824e-05" iyz="3.494431877242991e-07" izz="3.0474590214086944e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="left_link_right_jaw">
|
|
<visual>
|
|
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/right_jaw.stl"/>
|
|
</geometry>
|
|
<material name="gray"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
|
|
<geometry>
|
|
<mesh filename="package://openarm_description/meshes/right_jaw.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.042981665301134515"/>
|
|
<origin rpy="0 -0.00875818289800148 0" xyz="-0.0187844 -0.00272415 -0.0159503"/>
|
|
<inertia ixx="1.1561293087621594e-05" ixy="2.537718468008212e-06" ixz="-3.6591812257702003e-06" iyy="2.370165527871047e-05" iyz="4.848038235889027e-07" izz="3.039652946542647e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="left_rev1" type="revolute">
|
|
<parent link="left_link1"/>
|
|
<child link="left_link2"/>
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.05325"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev2" type="revolute">
|
|
<parent link="left_link2"/>
|
|
<child link="left_link3"/>
|
|
<origin rpy="-1.5707963267948968 0.0 0.0" xyz="0.0 -0.02975 0.04475"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="0" upper="3.141592653589793" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev3" type="revolute">
|
|
<parent link="left_link3"/>
|
|
<child link="left_link4"/>
|
|
<origin rpy="-1.5707963267949054 3.141592653589793 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-3.66519" upper="0.52359" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev4" type="revolute">
|
|
<parent link="left_link4"/>
|
|
<child link="left_link5"/>
|
|
<origin rpy="-0.20701608758495998 -1.5707963267948566 -2.937419385117548" xyz="0.0297547 0.0 -0.24175"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0.0" lower="-0.3490658503988659" upper="2.792526803190927" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev5" type="revolute">
|
|
<parent link="left_link5"/>
|
|
<child link="left_link6"/>
|
|
<origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev6" type="revolute">
|
|
<parent link="left_link6"/>
|
|
<child link="left_link7"/>
|
|
<origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_rev7" type="revolute">
|
|
<parent link="left_link7"/>
|
|
<child link="left_link8"/>
|
|
<origin rpy="-1.5707963267950005 -0.00875904933536772 -0.014066001454933467" xyz="-0.000217313 -0.0154485 0.0355"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.9599310885968813" upper="0.9599310885968813" velocity="0.0"/>
|
|
</joint>
|
|
<joint name="left_left_pris1" type="prismatic">
|
|
<parent link="left_link8"/>
|
|
<child link="left_link_left_jaw"/>
|
|
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
|
|
</joint>
|
|
<joint name="left_right_pris2" type="prismatic">
|
|
<parent link="left_link8"/>
|
|
<child link="left_link_right_jaw"/>
|
|
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
|
|
<mimic joint="left_left_pris1" multiplier="-1.0" offset="0.0"/>
|
|
</joint>
|
|
<joint name="left_virtual_gripper_center" type="fixed">
|
|
<parent link="left_link8"/>
|
|
<child link="left_gripper_center"/>
|
|
<origin rpy="0 0 0" xyz="-0.13 0.00 0.0132053"/>
|
|
</joint>
|
|
<joint name="left_fixed1" type="fixed">
|
|
<parent link="pedestal_link"/>
|
|
<child link="left_dummy_link"/>
|
|
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
|
|
</joint>
|
|
</robot>
|