Add openarm_bimanual_moveit_config and deploy to physical openarm (#3)

See https://github.com/reazon-research/openarm_ros2/pull/3 for video
This commit is contained in:
thomason 2025-04-10 18:31:15 +09:00 committed by GitHub
parent 42935bb3b1
commit 596c498598
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
60 changed files with 1750 additions and 438 deletions

2
.gitignore vendored
View File

@ -1 +1,3 @@
.DS_Store
.vscode/
__pycache__/

View File

@ -15,7 +15,7 @@ def generate_launch_description():
"openarm_bimanual_description"
)
)
default_model_path = pkg_share / "urdf/openarm_bimanual_wrapper.urdf.xacro"
default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro"
use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument("use_sim_time", default_value="true")

View File

@ -15,7 +15,7 @@ def generate_launch_description():
"openarm_bimanual_description"
)
)
default_model_path = pkg_share / "urdf/openarm_bimanual_wrapper.urdf.xacro"
default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro"
default_rviz_config_path = pkg_share / "rviz/robot_description.rviz"
use_sim_time = LaunchConfiguration("use_sim_time")

View File

@ -11,6 +11,7 @@
<depend>joint_state_publisher_gui</depend>
<depend>ros_gz</depend>
<depend>realsense2_description</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

View File

@ -4,10 +4,12 @@
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="openarm_bimanual">
<link name="world"/>
<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"/>
@ -30,276 +32,210 @@
<inertia ixx="0.6232810322991779" ixy="7.916644206828546e-12" ixz="-1.094192214704477e-11" iyy="0.6253514495087933" iyz="-0.03342233248166168" izz="0.02000994027356939"/>
</inertial>
</link>
<!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm -->
<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_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"/>
<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 0.0 -1.5707963267948966" xyz="0.0 -0.025 0.995216"/>
<parent link="pedestal_link"/>
<child link="camera_bottom_screw_frame"/>
</joint>
<joint name="right_rev2" type="revolute">
<parent link="right_link2"/>
<child link="right_link3"/>
<origin rpy="-1.5707963267948968 0 0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.0" upper="3.141592653589793" velocity="0.0"/>
<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>
<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="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
<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>
<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"/>
<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>
<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"/>
<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>
<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"/>
<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>
<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"/>
<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>
<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.0" upper="0.0451" velocity="0.0"/>
<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>
<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.0" upper="0.0451" velocity="0.0"/>
<mimic joint="right_left_pris1" multiplier="-1.0" offset="0.0"/>
<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="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"/>
@ -532,7 +468,7 @@
<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"/>
<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">
@ -546,7 +482,7 @@
<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"/>
<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">
@ -554,29 +490,371 @@
<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.0" upper="0.0451" velocity="0.0"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
</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.0" upper="0.0451" velocity="0.0"/>
<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="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>
<joint name="right_fixed1" type="fixed">
<parent link="pedestal_link"/>
<child link="left_link1"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</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>
<!-- 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_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" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.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="-3.6651914291880923" upper="0.5235987755982988" 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.0"/>
</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_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>
</robot>

View File

@ -1,25 +1,29 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<link name="world"/>
<xacro:include filename="$(find openarm_description)/urdf/openarm.xacro"/>
<xacro:include filename="openarm_pedestal.urdf"/>
<xacro:openarm prefix="right_" side="right" zero_pos="arm"/>
<xacro:openarm prefix="left_" side="left" zero_pos="arm"/>
<xacro:include filename="openarm_bimanual_sensors.xacro"/>
<link name="world"/>
<joint name="dummy_joint" type="fixed">
<parent link="world"/>
<child link="pedestal_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<joint name="left_fixed1" type="fixed">
<parent link="pedestal_link"/>
<child link="left_link1"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</joint>
<xacro:openarm prefix="right_" side="right" zero_pos="arm" can_device="can0"/>
<joint name="right_fixed1" type="fixed">
<parent link="pedestal_link"/>
<child link="right_link1"/>
<child link="right_dummy_link"/>
<origin rpy="${3.0186531925068127 + pi} -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/>
</joint>
<xacro:openarm prefix="left_" side="left" zero_pos="arm" can_device="can1"/>
<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>

View File

@ -1,5 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find realsense2_description)/urdf/_d435i.urdf.xacro"/>
<xacro:sensor_d435i parent="pedestal_link" use_nominal_extrinsics="true">
<origin xyz="0.0 -0.025 0.995216" rpy="0.0 0.0 ${-pi/2.0}"/>
</xacro:sensor_d435i>
</robot>

View File

@ -1,5 +0,0 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:include filename="openarm_bimanual.urdf.xacro"/>
<xacro:include filename="openarm_bimanual_sensors.xacro"/>
</robot>

View File

@ -0,0 +1,10 @@
moveit_setup_assistant_config:
urdf:
package: openarm_bimanual_description
relative_path: urdf/openarm_bimanual.urdf.xacro
srdf:
relative_path: config/openarm_bimanual.srdf
package_settings:
author_name: Thomason Zhou
author_email: t95zhou@uwaterloo.ca
generated_timestamp: 1744266716

View File

@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 3.22)
project(openarm_bimanual_moveit_config)
find_package(ament_cmake REQUIRED)
ament_package()
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/launch")
install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
PATTERN "setup_assistant.launch" EXCLUDE)
endif()
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})

View File

@ -0,0 +1,17 @@
# Default initial positions for openarm_bimanual's ros2_control fake system
initial_positions:
left_rev1: 0
left_rev2: 0
left_rev3: 0
left_rev4: 0
left_rev5: 0
left_rev6: 0
left_rev7: 0
right_rev1: 0
right_rev2: 0
right_rev3: 0
right_rev4: 0
right_rev5: 0
right_rev6: 0
right_rev7: 0

View File

@ -0,0 +1,90 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
left_left_pris1:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev1:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev2:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev3:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev4:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev5:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev6:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_rev7:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
left_right_pris2:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev1:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev2:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev3:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev4:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev5:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev6:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_rev7:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0

View File

@ -0,0 +1,4 @@
left_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001

View File

@ -0,0 +1,51 @@
Panels:
- Class: rviz_common/Displays
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- Class: rviz_common/Help
Name: Help
- Class: rviz_common/Views
Name: Views
Visualization Manager:
Displays:
- Class: rviz_default_plugins/Grid
Name: Grid
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
Name: MotionPlanning
Planned Path:
Loop Animation: true
State Display Time: 0.05 s
Trajectory Topic: display_planned_path
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Robot:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: world
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.0
Focal Point:
X: -0.1
Y: 0.25
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: world
Yaw: -0.623
Window Geometry:
Height: 975
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1200

View File

@ -0,0 +1,33 @@
# MoveIt uses this configuration for controller management
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- left_arm_controller
- right_arm_controller
left_arm_controller:
type: FollowJointTrajectory
joints:
- left_rev1
- left_rev2
- left_rev3
- left_rev4
- left_rev5
- left_rev6
- left_rev7
action_ns: follow_joint_trajectory
default: true
right_arm_controller:
type: FollowJointTrajectory
joints:
- right_rev1
- right_rev2
- right_rev3
- right_rev4
- right_rev5
- right_rev6
- right_rev7
action_ns: follow_joint_trajectory
default: true

View File

@ -0,0 +1,223 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="openarm_bimanual">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--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="left_arm">
<link name="left_link1"/>
<link name="left_link2"/>
<link name="left_link3"/>
<link name="left_link4"/>
<link name="left_link5"/>
<link name="left_link6"/>
<link name="left_link7"/>
<link name="left_link8"/>
<joint name="left_rev1"/>
<joint name="left_rev2"/>
<joint name="left_rev3"/>
<joint name="left_rev4"/>
<joint name="left_rev5"/>
<joint name="left_rev6"/>
<joint name="left_rev7"/>
<chain base_link="left_link1" tip_link="left_link8"/>
</group>
<group name="right_arm">
<link name="right_link1"/>
<link name="right_link2"/>
<link name="right_link3"/>
<link name="right_link4"/>
<link name="right_link5"/>
<link name="right_link6"/>
<link name="right_link7"/>
<link name="right_link8"/>
<joint name="right_rev1"/>
<joint name="right_rev2"/>
<joint name="right_rev3"/>
<joint name="right_rev4"/>
<joint name="right_rev5"/>
<joint name="right_rev6"/>
<joint name="right_rev7"/>
<chain base_link="right_link1" tip_link="right_link8"/>
</group>
<group name="left_gripper">
<link name="left_link_left_jaw"/>
<link name="left_link_right_jaw"/>
<joint name="left_left_pris1"/>
<joint name="left_right_pris2"/>
</group>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="left_gripper" parent_link="left_link8" group="left_arm"/>
<end_effector name="right_gripper" parent_link="right_link8" group="right_arm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="base_link" child_link="pedestal_link"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="left_link1" link2="left_link2" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="left_link3" reason="User"/>
<disable_collisions link1="left_link1" link2="left_link4" reason="User"/>
<disable_collisions link1="left_link1" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link1" link2="pedestal_link" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link3" reason="Adjacent"/>
<disable_collisions link1="left_link2" link2="left_link4" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link6" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link2" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link3" link2="left_link4" reason="Adjacent"/>
<disable_collisions link1="left_link3" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link3" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link5" reason="Adjacent"/>
<disable_collisions link1="left_link4" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link6" reason="Adjacent"/>
<disable_collisions link1="left_link5" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link8" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="left_link7" reason="Adjacent"/>
<disable_collisions link1="left_link6" link2="left_link8" reason="Default"/>
<disable_collisions link1="left_link6" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="left_link8" reason="Adjacent"/>
<disable_collisions link1="left_link7" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link8" link2="left_link_left_jaw" reason="Adjacent"/>
<disable_collisions link1="left_link8" link2="left_link_right_jaw" reason="Adjacent"/>
<disable_collisions link1="left_link8" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link1" reason="Adjacent"/>
<disable_collisions link1="pedestal_link" link2="right_link2" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link3" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link4" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link1" link2="right_link2" reason="Adjacent"/>
<disable_collisions link1="right_link1" link2="right_link3" reason="User"/>
<disable_collisions link1="right_link1" link2="right_link4" reason="User"/>
<disable_collisions link1="right_link1" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link3" reason="Adjacent"/>
<disable_collisions link1="right_link2" link2="right_link4" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link6" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link3" link2="right_link4" reason="Adjacent"/>
<disable_collisions link1="right_link3" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link5" reason="Adjacent"/>
<disable_collisions link1="right_link4" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link6" reason="Adjacent"/>
<disable_collisions link1="right_link5" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link8" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link6" link2="right_link7" reason="Adjacent"/>
<disable_collisions link1="right_link6" link2="right_link8" reason="Default"/>
<disable_collisions link1="right_link6" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link6" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link7" link2="right_link8" reason="Adjacent"/>
<disable_collisions link1="right_link7" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link7" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link8" link2="right_link_left_jaw" reason="Adjacent"/>
<disable_collisions link1="right_link8" link2="right_link_right_jaw" reason="Adjacent"/>
<disable_collisions link1="right_link_left_jaw" link2="right_link_right_jaw" reason="Never"/>
</robot>

View File

@ -0,0 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<!-- Import openarm_bimanual urdf file -->
<xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_bimanual.urdf.xacro" />
</robot>

View File

@ -0,0 +1,6 @@
# Limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
max_trans_dec: -5.0
max_rot_vel: 1.57

View File

@ -0,0 +1,48 @@
# This config file is used by ros2_control
controller_manager:
ros__parameters:
update_rate: 100 # Hz
left_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
right_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
left_arm_controller:
ros__parameters:
joints:
- left_rev1
- left_rev2
- left_rev3
- left_rev4
- left_rev5
- left_rev6
- left_rev7
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
right_arm_controller:
ros__parameters:
joints:
- right_rev1
- right_rev2
- right_rev3
- right_rev4
- right_rev5
- right_rev6
- right_rev7
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity

View File

@ -0,0 +1,25 @@
sensors:
- default_sensor
- kinect_depthimage
default_sensor:
far_clipping_plane_distance: 5.0
filtered_cloud_topic: filtered_cloud
image_topic: /head_mount_kinect/depth_registered/image_raw
max_update_rate: 1.0
near_clipping_plane_distance: 0.3
padding_offset: 0.03
padding_scale: 4.0
queue_size: 5
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
shadow_threshold: 0.2
kinect_depthimage:
far_clipping_plane_distance: 5.0
filtered_cloud_topic: filtered_cloud
image_topic: /head_mount_kinect/depth_registered/image_raw
max_update_rate: 1.0
near_clipping_plane_distance: 0.3
padding_offset: 0.03
padding_scale: 4.0
queue_size: 5
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
shadow_threshold: 0.2

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_demo_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_demo_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_move_group_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_moveit_rviz_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_rsp_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_rsp_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_setup_assistant_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_setup_assistant_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_spawn_controllers_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_spawn_controllers_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_static_virtual_joint_tfs_launch(moveit_config)

View File

@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_warehouse_db_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
return generate_warehouse_db_launch(moveit_config)

View File

@ -0,0 +1,49 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>openarm_bimanual_moveit_config</name>
<version>0.3.0</version>
<description>
An automatically generated package with all the configuration and launch files for using the openarm_bimanual with the MoveIt Motion Planning Framework
</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
<license>BSD</license>
<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/ros-planning/moveit2/issues</url>
<url type="repository">https://github.com/ros-planning/moveit2</url>
<author email="t95zhou@uwaterloo.ca">Thomason Zhou</author>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_kinematics</exec_depend>
<exec_depend>moveit_planners</exec_depend>
<exec_depend>moveit_simple_controller_manager</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>xacro</exec_depend>
<!-- The next 2 packages are required for the gazebo simulation.
We don't include them by default to prevent installing gazebo and all its dependencies. -->
<!-- <exec_depend>joint_trajectory_controller</exec_depend> -->
<!-- <exec_depend>gazebo_ros_control</exec_depend> -->
<exec_depend>controller_manager</exec_depend>
<exec_depend>moveit_configs_utils</exec_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_setup_assistant</exec_depend>
<exec_depend>openarm_bimanual_description</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>rviz_common</exec_depend>
<exec_depend>rviz_default_plugins</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -0,0 +1,30 @@
cmake_minimum_required(VERSION 3.8)
project(openarm_bimanual_teleop)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
install(DIRECTORY launch config
DESTINATION share/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View File

@ -0,0 +1,25 @@
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.

View File

@ -0,0 +1,50 @@
controller_manager:
ros__parameters:
update_rate: 100 # Hz
left_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
right_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broad:
type: joint_state_broadcaster/JointStateBroadcaster
left_arm_controller:
ros__parameters:
joints:
- left_rev1
- left_rev2
- left_rev3
- left_rev4
- left_rev5
- left_rev6
- left_rev7
command_interfaces:
- position
- velocity
- effort
state_interfaces:
- position
- velocity
- effort
right_arm_controller:
ros__parameters:
joints:
- right_rev1
- right_rev2
- right_rev3
- right_rev4
- right_rev5
- right_rev6
- right_rev7
command_interfaces:
- position
- velocity
- effort
state_interfaces:
- position
- velocity
- effort

View File

@ -0,0 +1,15 @@
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
realsense_share_dir = FindPackageShare("realsense2_camera")
rs_launch_path = [realsense_share_dir, "/launch/rs_launch.py"]
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource(rs_launch_path),
launch_arguments={"pointcloud.enable": "true"}.items()
)
])

View File

@ -0,0 +1,83 @@
import launch
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, TimerAction, RegisterEventHandler
from launch.event_handlers import OnProcessStart
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, Command
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch_ros.parameter_descriptions import ParameterValue
from launch.launch_description_sources import PythonLaunchDescriptionSource
import pathlib
def generate_launch_description():
pkg_share = FindPackageShare(package="openarm_bimanual_description")
xacro_path = pathlib.Path(pkg_share.find(
"openarm_bimanual_description"
)) / "urdf/openarm_bimanual.urdf.xacro"
use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument(name="use_sim_time", default_value="false")
robot_state_publisher_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
pkg_share,
"launch",
"description.launch.py",
]
),
]
),
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
robot_description_content = Command([
'xacro ', LaunchConfiguration("model")
])
robot_description_param = {'robot_description': ParameterValue(robot_description_content, value_type=str)}
controller_params = PathJoinSubstitution([
FindPackageShare(package='openarm_bimanual_teleop'),
'config',
'controllers.yaml'
])
controller_manager = Node(
package='controller_manager',
executable='ros2_control_node',
parameters=[controller_params, robot_description_param],)
delayed_controller_manager = TimerAction(period=3.0, actions=[controller_manager])
joint_broadcaster_spawner = Node(
package='controller_manager',
executable='spawner',
arguments=['joint_state_broad'],
)
delayed_joint_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessStart(
target_action=controller_manager,
on_start=[joint_broadcaster_spawner],
)
)
return launch.LaunchDescription(
[
DeclareLaunchArgument(
name="model",
default_value=str(xacro_path),
description="Absolute path to the robot URDF or xacro file"
),
use_sim_time_launch_arg,
robot_state_publisher_node,
delayed_controller_manager,
delayed_joint_broadcaster_spawner
]
)

View File

@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>openarm_bimanual_teleop</name>
<version>0.0.0</version>
<description>Teleoperation setup for bimanual openarm</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
<license>BSD-3-Clause</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -72,7 +72,7 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"use_mock_hardware",
default_value="true",
default_value="false",
description="Start robot with mock hardware mirroring command to its states.",
)
)

View File

@ -0,0 +1,15 @@
#!/bin/bash
# This script initializes the CAN interface on a Linux system.
echo Using CAN interface: $1 with $2
if [ ! -e $1 ]; then
echo "Device $1 does not exist."
exit 1
fi
bitrate=1000000
sudo slcand -o -c -s8 $1
sudo ip link set $2 type can bitrate $bitrate
sudo ip link set $2 up
sudo ip link show $2

View File

@ -15,7 +15,7 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()
install(DIRECTORY launch meshes rviz urdf worlds
install(DIRECTORY launch meshes rviz urdf worlds config
DESTINATION share/${PROJECT_NAME}
)

View File

@ -17,9 +17,39 @@ def generate_launch_description():
)
default_model_path = pkg_share / "urdf/openarm.urdf.xacro"
model_arg = launch.actions.DeclareLaunchArgument(
name="model",
default_value=str(default_model_path),
description="Absolute path to the robot's URDF file",
)
side_arg = DeclareLaunchArgument(
name="side", default_value="right", # Use "left" to test left arm.
description="Select arm side: 'left' or 'right'"
)
zero_pos_arg = DeclareLaunchArgument(
name="zero_pos", default_value="up", # Use "arm" to test alternative configuration.
description="Specify zero position: 'up' or 'arm'"
)
prefix_arg = DeclareLaunchArgument(
name="prefix", default_value="",
description="Prefix for link and joint names (e.g., left_, right_)"
)
can_device_arg = DeclareLaunchArgument(
name="can_device", default_value="can0",
description="CAN device identifier to use"
)
use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument("use_sim_time", default_value="true")
robot_description_command = Command([
"xacro ", LaunchConfiguration("model"),
" side:=", LaunchConfiguration("side"),
" zero_pos:=", LaunchConfiguration("zero_pos"),
" prefix:=", LaunchConfiguration("prefix"),
" can_device:=", LaunchConfiguration("can_device")
])
robot_state_publisher_node = launch_ros.actions.Node(
package="robot_state_publisher",
executable="robot_state_publisher",
@ -27,7 +57,7 @@ def generate_launch_description():
{
# ParameterValue is required to avoid being interpreted as YAML.
"robot_description": ParameterValue(
Command(["xacro ", LaunchConfiguration("model")]), value_type=str
robot_description_command, value_type=str
),
"use_sim_time": use_sim_time,
},
@ -36,11 +66,11 @@ def generate_launch_description():
return launch.LaunchDescription(
[
launch.actions.DeclareLaunchArgument(
name="model",
default_value=str(default_model_path),
description="Absolute path to the robot's URDF file",
),
model_arg,
side_arg,
zero_pos_arg,
prefix_arg,
can_device_arg,
use_sim_time_launch_arg,
robot_state_publisher_node,
]

View File

@ -1,21 +1,21 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:=''">
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:='' can_device='can0'">
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
<ros2_control name="${prefix}${name}" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
<!-- <plugin>mock_components/GenericSystem</plugin> -->
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">${prefix}</param>
<param name="can_device">${can_device}</param>
</hardware>
<joint name="${prefix}rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev1']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -23,9 +23,7 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev2']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -33,9 +31,7 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev3']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -43,9 +39,7 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev4']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -53,9 +47,7 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev5']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -63,9 +55,7 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev6']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
@ -73,25 +63,21 @@
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['rev7']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}left_pris1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_pris1']}</param>
</state_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="${prefix}right_pris2">
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['left_pris1']}</param>
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint>
</joint> -->
</ros2_control>
</xacro:macro>

View File

@ -7,14 +7,19 @@
<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>
<!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm -->
<ros2_control name="OpenArmHW" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
<!-- <plugin>mock_components/GenericSystem</plugin> -->
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix"></param>
<param name="can_device">can0</param>
</hardware>
<joint name="rev1">
<command_interface name="position"/>
@ -93,12 +98,17 @@
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_pris2">
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
</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="dummy_link"/>
<joint name="dummy_joint" type="fixed">
<parent link="dummy_link"/>
<child link="link1"/>
</joint>
<link name="link1">
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>

View File

@ -2,7 +2,5 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm">
<xacro:include filename="openarm.xacro"/>
<xacro:openarm/>
<xacro:include filename="openarm_sensors.xacro"/>
<xacro:include filename="openarm.ros2_control.xacro" />
<xacro:openarm_ros2_control name="OpenArmHW" prefix="${prefix}" initial_positions_file="$(arg initial_positions_file)"/>
<xacro:include filename="$(find openarm_description)/urdf/openarm_sensors.xacro"/>
</robot>

View File

@ -4,8 +4,11 @@
<material name="gray">
<color rgba="${105/255} ${105/255} ${105/255} 1.0"/>
</material>
<material name="dark_gray">
<color rgba="${50/255} ${50/255} ${50/255} 1.0"/>
</material>
<xacro:macro name="openarm" params="side:='right' prefix:='' zero_pos='up'">
<xacro:macro name="openarm" params="side:='right' prefix:='' zero_pos='up' can_device='can0'">
<!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm -->
@ -14,7 +17,16 @@
<xacro:property name="reflect" value="${1 if side=='right' else -1}"/>
<xacro:property name="rotate" value="${0 if side=='right' else pi}"/>
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro" />
<xacro:arg name="initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="OpenArmHW" prefix="${prefix}" initial_positions_file="$(arg initial_positions_file)" can_device="${can_device}"/>
<link name="${prefix}dummy_link"/>
<joint name="${prefix}dummy_joint" type="fixed">
<parent link="${prefix}dummy_link"/>
<child link="${prefix}link1"/>
</joint>
<link name="${prefix}link1">
<visual>
@ -220,21 +232,21 @@
<parent link="${prefix}link1"/>
<child link="${prefix}link2"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.05325"/>
<axis xyz="0 0 ${reflect*1}"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="${prefix}rev2" type="revolute">
<parent link="${prefix}link2"/>
<child link="${prefix}link3"/>
<origin rpy="-1.5707963267948968 ${pi/2 if zero_pos=='up' else 0} 0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="${-pi/2.0 if zero_pos=='up' else 0.0}" upper="${pi/2 if zero_pos=='up' else pi}" velocity="0.0"/>
<origin rpy="-1.5707963267948968 ${pi/2 if zero_pos=='up' else 0.0} 0.0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 ${reflect * -1}"/>
<limit effort="0.0" lower="${-pi/2.0 if zero_pos=='up' else -pi + rotate}" upper="${pi/2 if zero_pos=='up' else 0 + rotate}" velocity="0.0"/>
</joint>
<joint name="${prefix}rev3" type="revolute">
<parent link="${prefix}link3"/>
<child link="${prefix}link4"/>
<origin rpy="-1.5707963267949054 ${rotate} -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 ${reflect*1}"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
</joint>
<joint name="${prefix}rev4" type="revolute">
@ -248,21 +260,21 @@
<parent link="${prefix}link5"/>
<child link="${prefix}link6"/>
<origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="${prefix}rev6" type="revolute">
<parent link="${prefix}link6"/>
<child link="${prefix}link7"/>
<origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 ${reflect}"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>
<joint name="${prefix}rev7" type="revolute">
<parent link="${prefix}link7"/>
<child link="${prefix}link8"/>
<origin rpy="-1.5707963267950005 -0.00875904933536772 -0.014066001454933467" xyz="-0.000217313 -0.0154485 0.0355"/>
<axis xyz="0 0 1"/>
<axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.9599310885968813" upper="0.9599310885968813" velocity="0.0"/>
</joint>
<joint name="${prefix}left_pris1" type="prismatic">
@ -270,14 +282,14 @@
<child link="${prefix}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.0" upper="0.0451" velocity="0.0"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
</joint>
<joint name="${prefix}right_pris2" type="prismatic">
<parent link="${prefix}link8"/>
<child link="${prefix}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.0" upper="0.0451" velocity="0.0"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="${prefix}left_pris1" multiplier="-1.0" offset="0.0"/>
</joint>
</xacro:macro>

View File

@ -16,12 +16,15 @@ find_package(rclcpp_lifecycle REQUIRED)
add_library(${PROJECT_NAME} SHARED
src/openarm_hardware.cpp
src/canbus.cpp
src/motor.cpp
src/motor_control.cpp
)
target_include_directories(${PROJECT_NAME}
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
target_include_directories(
${PROJECT_NAME}
PRIVATE
include
)
ament_target_dependencies(${PROJECT_NAME}
@ -30,24 +33,23 @@ ament_target_dependencies(${PROJECT_NAME}
rclcpp
rclcpp_lifecycle
)
ament_export_libraries(${PROJECT_NAME})
pluginlib_export_plugin_description_file(hardware_interface openarm_hardware.xml)
install(
TARGETS ${PROJECT_NAME}
DESTINATION lib
)
install(DIRECTORY include/
DESTINATION include
DESTINATION include
)
install(TARGETS ${PROJECT_NAME}
DESTINATION bin
)
install(FILES
openarm_hardware.xml
DESTINATION share/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(hardware_interface REQUIRED)
ament_add_gmock(test_openarm_hardware
test/test_openarm_hardware.cpp
@ -64,4 +66,18 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()
ament_export_include_directories(
include
)
ament_export_libraries(
${PROJECT_NAME}
)
ament_export_dependencies(
hardware_interface
pluginlib
rclcpp
)
ament_package()

View File

@ -35,13 +35,22 @@
namespace openarm_hardware
{
const std::vector<DM_Motor_Type> MOTORS_TYPES = {DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4310, DM_Motor_Type::DM4310, DM_Motor_Type::DM4310};
const std::vector<uint16_t> CAN_DEVICE_IDS = {0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
const std::vector<uint16_t> CAN_MASTER_IDS = {0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17};
const std::vector<bool> MOTOR_WITH_TORQUE = {true,true,true,true,true,true,true};
const Control_Type CONTROL_MODE = Control_Type::MIT;
const double DEFAULT_KP = 1.0;
const double DEFAULT_KD = 0.0;
std::vector<DM_Motor_Type> motor_types{DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4340, DM_Motor_Type::DM4310, DM_Motor_Type::DM4310, DM_Motor_Type::DM4310};
std::vector<uint16_t> can_device_ids{0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
std::vector<uint16_t> can_master_ids{0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17};
static const Control_Type CONTROL_MODE = Control_Type::MIT;
static const std::size_t ARM_DOF = 7;
static const std::size_t GRIPPER_DOF = 1;
static const std::size_t TOTAL_DOF = ARM_DOF + GRIPPER_DOF;
static const std::array<double, TOTAL_DOF> KP = {80.0, 80.0, 20.0, 55.0, 5.0, 5.0, 5.0, 0.5};
static const std::array<double, TOTAL_DOF> KD = {1.25, 0.17, 0.015, 0.07, 0.07, 0.05, 0.05, 0.01};
static const std::array<double, TOTAL_DOF> SLOW_KP = {10.0, 10.0, 10.0, 7.5, 5.0, 5.0, 5.0, 0.5};
static const double START_POS_TOLERANCE_RAD = 0.1;
static const double POS_JUMP_TOLERANCE_RAD = 3.1415 / 2.0;
static const bool USING_GRIPPER = true;
static const double GRIPPER_REFERENCE_GEAR_RADIUS_M = 0.00853;
static const int GRIPPER_INDEX = TOTAL_DOF - 1;
class OpenArmHW : public hardware_interface::SystemInterface
{
@ -78,9 +87,11 @@ public:
hardware_interface::return_type write(
const rclcpp::Time & time, const rclcpp::Duration & period) override;
std::size_t curr_dof = ARM_DOF; // minus gripper
private:
std::string prefix_;
std::unique_ptr<CANBus> canbus_;
MotorControl motor_control_;
std::unique_ptr<MotorControl> motor_control_;
std::vector<double> pos_commands_;
std::vector<double> pos_states_;
std::vector<double> vel_commands_;
@ -88,6 +99,9 @@ private:
std::vector<double> tau_ff_commands_;
std::vector<double> tau_states_;
std::vector<std::unique_ptr<Motor>> motors_;
void refresh_motors();
bool disable_torque_;
};
} // namespace openarm_hardware

View File

@ -1,4 +1,4 @@
#include "canbus.hpp"
#include "openarm_hardware/canbus.hpp"
#include <poll.h>
CANBus::CANBus(const std::string& interface) {

View File

@ -1,4 +1,4 @@
#include "motor.hpp"
#include "openarm_hardware/motor.hpp"
Motor::Motor(DM_Motor_Type motorType, uint16_t slaveID, uint16_t masterID)
: MotorType(motorType), SlaveID(slaveID), MasterID(masterID),

View File

@ -1,5 +1,5 @@
#include "motor_control.hpp"
#include "motor.hpp"
#include "openarm_hardware/motor_control.hpp"
#include "openarm_hardware/motor.hpp"
MotorControl::MotorControl(CANBus& canbus) : canbus_(canbus) {}

View File

@ -19,22 +19,14 @@
#include "openarm_hardware/openarm_hardware.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/logging.hpp"
namespace openarm_hardware
{
static const std::string& can_device_name = "can0";
OpenArmHW::OpenArmHW():
canbus_(std::make_unique<CANBus>(can_device_name)),
motor_control_(MotorControl(*canbus_)) {
for(size_t i = 0; i < MOTORS_TYPES.size(); ++i){
motors_[i] = std::make_unique<Motor>(MOTORS_TYPES[i], CAN_DEVICE_IDS[i], CAN_MASTER_IDS[i]);
}
for(const auto& motor: motors_){
motor_control_.addMotor(*motor);
}
}
OpenArmHW::OpenArmHW() = default;
hardware_interface::CallbackReturn OpenArmHW::on_init(
const hardware_interface::HardwareInfo & info)
@ -44,12 +36,54 @@ hardware_interface::CallbackReturn OpenArmHW::on_init(
return CallbackReturn::ERROR;
}
pos_states_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
pos_commands_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
vel_states_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
vel_commands_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
tau_states_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
tau_ff_commands_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
//read hardware parameters
if (info.hardware_parameters.find("can_device") == info.hardware_parameters.end()){
RCLCPP_ERROR(rclcpp::get_logger("OpenArmHW"), "No can_device parameter found");
return CallbackReturn::ERROR;
}
auto it = info.hardware_parameters.find("prefix");
if (it == info.hardware_parameters.end()){
prefix_ = "";
}
else{
prefix_ = it->second;
}
it = info.hardware_parameters.find("disable_torque");
if (it == info.hardware_parameters.end()){
disable_torque_ = false;
}
else{
disable_torque_ = it->second == "true";
}
canbus_ = std::make_unique<CANBus>(info.hardware_parameters.at("can_device"));
motor_control_ = std::make_unique<MotorControl>(*canbus_);
if(USING_GRIPPER){
motor_types.emplace_back(DM_Motor_Type::DM4310);
can_device_ids.emplace_back(0x08);
can_master_ids.emplace_back(0x18);
++curr_dof;
}
motors_.resize(curr_dof);
for(size_t i = 0; i < curr_dof; ++i){
motors_[i] = std::make_unique<Motor>(motor_types[i], can_device_ids[i], can_master_ids[i]);
}
for(const auto& motor: motors_){
motor_control_->addMotor(*motor);
}
pos_states_.resize(curr_dof, 0.0);
pos_commands_.resize(curr_dof, 0.0);
vel_states_.resize(curr_dof, 0.0);
vel_commands_.resize(curr_dof, 0.0);
tau_states_.resize(curr_dof, 0.0);
tau_ff_commands_.resize(curr_dof, 0.0);
refresh_motors();
read(rclcpp::Time(0), rclcpp::Duration(0, 0));
return CallbackReturn::SUCCESS;
}
@ -57,7 +91,14 @@ hardware_interface::CallbackReturn OpenArmHW::on_init(
hardware_interface::CallbackReturn OpenArmHW::on_configure(
const rclcpp_lifecycle::State & /*previous_state*/)
{
read(rclcpp::Time(0), rclcpp::Duration(0, 0));
// zero position or calibrate to pose
// for (std::size_t i = 0; i < curr_dof; ++i)
// {
// motor_control_->set_zero_position(*motors_[i]);
// }
return CallbackReturn::SUCCESS;
}
@ -65,11 +106,12 @@ hardware_interface::CallbackReturn OpenArmHW::on_configure(
std::vector<hardware_interface::StateInterface> OpenArmHW::export_state_interfaces()
{
std::vector<hardware_interface::StateInterface> state_interfaces;
for (size_t i = 0; i < info_.joints.size(); ++i)
for (size_t i = 0; i < curr_dof; ++i)
{
state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_POSITION, &pos_states_[i]));
state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &vel_states_[i]));
state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_EFFORT, &tau_states_[i]));
RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Exporting state interface for joint %s", info_.joints[i].name.c_str());
}
return state_interfaces;
@ -78,7 +120,7 @@ std::vector<hardware_interface::StateInterface> OpenArmHW::export_state_interfac
std::vector<hardware_interface::CommandInterface> OpenArmHW::export_command_interfaces()
{
std::vector<hardware_interface::CommandInterface> command_interfaces;
for (size_t i = 0; i < info_.joints.size(); ++i)
for (size_t i = 0; i < curr_dof; ++i)
{
command_interfaces.emplace_back(hardware_interface::CommandInterface(info_.joints[i].name, hardware_interface::HW_IF_POSITION, &pos_commands_[i]));
command_interfaces.emplace_back(hardware_interface::CommandInterface(info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &vel_commands_[i]));
@ -88,11 +130,37 @@ std::vector<hardware_interface::CommandInterface> OpenArmHW::export_command_inte
return command_interfaces;
}
void OpenArmHW::refresh_motors()
{
for(const auto& motor: motors_){
motor_control_->controlMIT(*motor, 0.0, 0.0, 0.0, 0.0, 0.0);
}
}
hardware_interface::CallbackReturn OpenArmHW::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
read(rclcpp::Time(0), rclcpp::Duration(0, 0));
// for (std::size_t m = 0; m < curr_dof; ++m){
// double diff = pos_states_[m] - pos_commands_[m];
// while(abs(diff) > START_POS_TOLERANCE_RAD){
// // linear interpolation
// // take the min of max_step and the difference
// double max_step = std::min(POS_JUMP_TOLERANCE_RAD, std::abs(diff));
// if (diff > 0){
// pos_commands_[m] = pos_states_[m] - max_step;
// }
// else{
// pos_commands_[m] = pos_states_[m] + max_step;
// }
// motor_control_->controlMIT(*motors_[m], SLOW_KP[m], KD[m], pos_commands_[m], 0.0, 0.0);
// }
// }
refresh_motors();
for(const auto& motor: motors_){
motor_control_.enable(*motor);
motor_control_->enable(*motor);
}
read(rclcpp::Time(0), rclcpp::Duration(0, 0));
@ -102,8 +170,9 @@ hardware_interface::CallbackReturn OpenArmHW::on_activate(
hardware_interface::CallbackReturn OpenArmHW::on_deactivate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
refresh_motors();
for(const auto& motor: motors_){
motor_control_.disable(*motor);
motor_control_->disable(*motor);
}
return CallbackReturn::SUCCESS;
@ -112,11 +181,17 @@ hardware_interface::CallbackReturn OpenArmHW::on_deactivate(
hardware_interface::return_type OpenArmHW::read(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
for(size_t i = 0; i < motors_.size(); ++i){
for(size_t i = 0; i < ARM_DOF; ++i){
pos_states_[i] = motors_[i]->getPosition();
vel_states_[i] = motors_[i]->getVelocity();
tau_states_[i] = motors_[i]->getTorque();
}
if(USING_GRIPPER){
pos_states_[GRIPPER_INDEX] = -motors_[GRIPPER_INDEX]->getPosition() * GRIPPER_REFERENCE_GEAR_RADIUS_M;
vel_states_[GRIPPER_INDEX] = motors_[GRIPPER_INDEX]->getVelocity() * GRIPPER_REFERENCE_GEAR_RADIUS_M;
tau_states_[GRIPPER_INDEX] = motors_[GRIPPER_INDEX]->getTorque() * GRIPPER_REFERENCE_GEAR_RADIUS_M;
}
return hardware_interface::return_type::OK;
}
@ -124,8 +199,27 @@ hardware_interface::return_type OpenArmHW::read(
hardware_interface::return_type OpenArmHW::write(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
for(size_t i = 0; i < motors_.size(); ++i){
motor_control_.controlMIT(*motors_[i], DEFAULT_KP, DEFAULT_KD, pos_commands_[i], vel_commands_[i], tau_ff_commands_[i]);
disable_torque_ = false;
if (disable_torque_){
// refresh motor state on write
for(size_t i = 0; i < TOTAL_DOF; ++i){
motor_control_->controlMIT(*motors_[i], 0.0, 0.0, 0.0, 0.0, 0.0);
return hardware_interface::return_type::OK;
}
}
for(size_t i = 0; i < ARM_DOF; ++i){
if (std::abs(pos_commands_[i] - pos_states_[i]) > POS_JUMP_TOLERANCE_RAD)
{
RCLCPP_ERROR(rclcpp::get_logger("OpenArmHW"), "Position jump detected for joint %s: %f -> %f", info_.joints[i].name.c_str(), pos_states_[i], pos_commands_[i]);
return hardware_interface::return_type::ERROR;
}
motor_control_->controlMIT(*motors_[i], KP.at(i), KD.at(i), pos_commands_[i], vel_commands_[i], tau_ff_commands_[i]);
}
if(USING_GRIPPER){
motor_control_->controlMIT(*motors_[GRIPPER_INDEX], KP.at(GRIPPER_INDEX), KD.at(GRIPPER_INDEX), -pos_commands_[GRIPPER_INDEX] / GRIPPER_REFERENCE_GEAR_RADIUS_M, vel_commands_[GRIPPER_INDEX] / GRIPPER_REFERENCE_GEAR_RADIUS_M, tau_ff_commands_[GRIPPER_INDEX] / GRIPPER_REFERENCE_GEAR_RADIUS_M);
}
return hardware_interface::return_type::OK;
}

View File

@ -7,25 +7,4 @@ moveit_setup_assistant_config:
package_settings:
author_name: Thomason Zhou
author_email: t95zhou@uwaterloo.ca
generated_timestamp: 1741767765
control_xacro:
command:
- position
- velocity
- effort
state:
- position
- velocity
- effort
modified_urdf:
xacros:
- control_xacro
control_xacro:
command:
- position
- velocity
- effort
state:
- position
- velocity
- effort
generated_timestamp: 1744186910

View File

@ -2,7 +2,6 @@
initial_positions:
left_pris1: 0
right_pris2: 0
rev1: 0
rev2: 0
rev3: 0

View File

@ -13,11 +13,6 @@ joint_limits:
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
right_pris2:
has_velocity_limits: false
max_velocity: 0
has_acceleration_limits: false
max_acceleration: 0
rev1:
has_velocity_limits: false
max_velocity: 0

View File

@ -27,7 +27,7 @@ Visualization Manager:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: link1
Fixed Frame: dummy_link
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
@ -43,7 +43,7 @@ Visualization Manager:
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: link1
Target Frame: dummy_link
Yaw: -0.623
Window Geometry:
Height: 975

View File

@ -17,6 +17,8 @@ moveit_simple_controller_manager:
- rev5
- rev6
- rev7
action_ns: follow_joint_trajectory
default: true
gripper_controller:
type: GripperCommand
joints:

View File

@ -55,7 +55,7 @@
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="gripper" parent_link="link8" group="gripper" parent_group="openarm_arm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="link1"/>
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="dummy_link"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="link1" link2="link2" reason="Adjacent"/>
<disable_collisions link1="link1" link2="link3" reason="Never"/>

View File

@ -1,5 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm">
<!-- Import openarm urdf file -->
<xacro:include filename="$(find openarm_description)/urdf/openarm.urdf" />
<xacro:include filename="$(find openarm_description)/urdf/openarm.urdf.xacro" />
</robot>

View File

@ -30,9 +30,6 @@ openarm_arm_controller:
command_interfaces:
- position
- velocity
- effort
state_interfaces:
- position
- velocity
- effort
allow_nonzero_velocity_at_trajectory_end: false

View File

@ -0,0 +1,25 @@
sensors:
- default_sensor
- kinect_depthimage
default_sensor:
far_clipping_plane_distance: 5.0
filtered_cloud_topic: filtered_cloud
image_topic: /head_mount_kinect/depth_registered/image_raw
max_update_rate: 1.0
near_clipping_plane_distance: 0.3
padding_offset: 0.03
padding_scale: 4.0
queue_size: 5
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
shadow_threshold: 0.2
kinect_depthimage:
far_clipping_plane_distance: 5.0
filtered_cloud_topic: filtered_cloud
image_topic: /head_mount_kinect/depth_registered/image_raw
max_update_rate: 1.0
near_clipping_plane_distance: 0.3
padding_offset: 0.03
padding_scale: 4.0
queue_size: 5
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
shadow_threshold: 0.2

View File

@ -8,11 +8,11 @@
</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
<license>BSD-3-Clause</license>
<license>BSD</license>
<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/moveit/moveit2/issues</url>
<url type="repository">https://github.com/moveit/moveit2</url>
<url type="bugtracker">https://github.com/ros-planning/moveit2/issues</url>
<url type="repository">https://github.com/ros-planning/moveit2</url>
<author email="t95zhou@uwaterloo.ca">Thomason Zhou</author>
@ -43,7 +43,6 @@
<exec_depend>rviz_default_plugins</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>warehouse_ros_mongo</exec_depend>
<exec_depend>xacro</exec_depend>
<export>