Skip to content

Commit 62cad42

Browse files
RobotawiAndyZeAndy Zelenak
authored
Tutorial for multiple robot arms with MoveIt (#708)
* add pkg config files * include multiple arms tutorial * add multiple arms tutorial images * include required steps for multiple arms tutorial * update step one explanation * resize intro image * update step 2 * update step 3 * fix a typo * Include gazebo arg in arms xacro * Update after using gazebo-ready xacro * Include arms ready poses fig * Update joints hw interface and controllers * Add world link and base inertia * Separate joint state and trajectory controllers * update step three * embed video * Remove emeding and add a YouTube video link * Remove lengthy xacro file and add a link to it * Explain xacro loading practice * Format steps to test xacro * Update check_urdf output * Configure ros controllers and moveit controllers * Update the video link and description * Explain the integration components * Start step five to plan motions for arms/hands * Add the motion planning step * Fix typos * Minimal fixes for the content * Fix plugin name * Fix language errors * Fix faulty files paths * Correct file names * Remove unneeded comments * Correct controllers config files format * Explicitly instruct to copy xacro file content * Revise step 1 * Revise step 1 * Fix robot_description path * Update rviz screenshot to use world frame * Conclude step 1 * Revise step 2 * Reformat step 3 * Revise step 3 * Revise step 4 * Explain integration dependencies * Fix ROS and MoveIt abbreviations * Revise step 5 * Fix minimal formatting issues * Fix error due to duplicate hyperlink target * Proofread and include references * Update doc/multiple_robot_arms/multiple_robot_arms_tutorial.rst Co-authored-by: AndyZe <[email protected]> * Change rgt to right and lft to left * Update screenshots to show right and left * Delete unneeded files * Shorten the motion planning step * Minimal fix to the target link position * Fix the title of the tutorial * Remove the word "MoveIt" from the title * Grammar nitpicks * Mention a move_group for both arms * Update url * Formatting Co-authored-by: AndyZe <[email protected]> Co-authored-by: Andy Zelenak <[email protected]>
1 parent 71ab5ee commit 62cad42

File tree

8 files changed

+529
-1
lines changed

8 files changed

+529
-1
lines changed

doc/mesh_filter/mesh_filter_tutorial.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ Include sensor plugin in a ``.gazebo`` file. In this tutorial, a kinect sensor p
8282
</gazebo>
8383

8484

85-
Attach sensor to `base urdf <https://github.com/ros-industrial/universal_robot/blob/melodic-devel/ur_description/urdf/ur5.urdf.xacro>`_ of UR5 using links and joints as shown in ``ur5_sensor.urdf.xacro`` ::
85+
Attach sensor to `base urdf <https://github.com/ros-industrial/universal_robot/blob/melodic-devel/ur_description/urdf/ur5.xacro>`_ of UR5 using links and joints as shown in ``ur5_sensor.urdf.xacro`` ::
8686

8787
<!-- ur5 -->
8888
<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />
97 KB
Loading
86.8 KB
Loading
107 KB
Loading
85.5 KB
Loading
19.4 KB
Loading

doc/multiple_robot_arms/multiple_robot_arms_tutorial.rst

Lines changed: 527 additions & 0 deletions
Large diffs are not rendered by default.

index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@ Before attempting to integrate a new robot with MoveIt, check whether your robot
6868
doc/ikfast/ikfast_tutorial
6969
doc/trac_ik/trac_ik_tutorial
7070
doc/opw_kinematics/opw_kinematics_tutorial
71+
doc/multiple_robot_arms/multiple_robot_arms_tutorial
7172

7273
Configuration
7374
-------------

0 commit comments

Comments
 (0)