This page tutorial describes how to use Sawyer with MoveIt! the standard ROS motion planning framework.
Please visit the MOVEIT! homepage for more information.
Contents
- Contents
- Installation/Prerequisites
- Overview
- Tutorial
- Interfaces
- Related Examples/Tutorials
- Troubleshooting
Installation/Prerequisites
- Make sure you have followed the Workstation Setup tutorial before beginning this section.
Installing MoveIt
ROS Noetic | = Make sure to update your sources =
$ sudo apt-get update
= Install MoveIt! =
$ sudo apt-get install ros-noetic-moveit |
ROS Melodic | = Make sure to update your sources =
$ sudo apt-get update
= Install MoveIt! =
$ sudo apt-get install ros-melodic-moveit |
ROS Kinetic | = Make sure to update your sources =
$ sudo apt-get update
= Install MoveIt! =
$ sudo apt-get install ros-kinetic-moveit |
ROS Indigo | = Make sure to update your sources =
$ sudo apt-get update
= Install MoveIt! =
$ sudo apt-get install ros-indigo-moveit |
Installing and Building Sawyer MoveIt Repo
Run catkin_make
to make the new Sawyer MoveIt! additions to your ROS workspace
ROS Noetic/Melodic | $ cd ~/ros_ws/
$ ./intera.sh
$ cd ~/ros_ws/src
$ wstool merge https://raw.githubusercontent.com/RethinkRobotics/sawyer_moveit/melodic_devel/sawyer_moveit.rosinstall
$ wstool update
$ cd ~/ros_ws/
$ catkin_make |
ROS Kinetic/Indigo | $ cd ~/ros_ws/
$ ./intera.sh
$ cd ~/ros_ws/src
$ wstool merge https://raw.githubusercontent.com/RethinkRobotics/sawyer_moveit/master/sawyer_moveit.rosinstall
$ wstool update
$ cd ~/ros_ws/
$ catkin_make |
Overview
MoveIt! motion planning framework provides capabilities including Kinematics (IK, FK, Jacobian), Motion Planning (OMPL, SBPL, CHOMP) integrated as MoveIt! plugins, Environment Representation (robot representation, environment representation, collision checking, contraint evaluation), execution using move_groups, benchmarking, warehouse database for storage (scenes, robot states, motion plans), a C++/Python API and more!
Sawyer now supports using MoveIt! through the addition of the configurable joint trajectory action server, and hosting of the necessary MoveIt! configuration files on RethinkRobotics/sawyer_moveit.
This tutorial will focus on the MoveIt! Rviz plugin as an introduction to some of the capabilities of MoveIt!
Sawyer Planning Groups
Describes the joints considered during motion planning. These are specified in the SRDF for Sawyer. Sawyer's SRDF includes planning groups, additional collision checking information, and default configurations. These groups are generated dynamically via Xacro
Planning Group
- right_arm
- chainbase -> right_gripper
- right_j0
- right_j1
- right_j2
- right_j3
- right_j4
- right_j5
- right_j6
- right_hand
- right_gripper
- chainbase -> right_gripper
- right_hand
- right_hand
- right_gripper
The SRDF is generated dynamically at runtime and then loaded to the param server under robot_semantic_description. You can view the top level SRDF Xacro file under sawyer_moveit_config/config/sawyer.srdf.xacro
Tutorial
Verify that the robot is enabled from an SDK terminal session, ex:
$ rosrun intera_interface enable_robot.py -e
Start the joint trajectory controller, ex:
$ rosrun intera_interface joint_trajectory_action_server.py
In another SDK terminal session, Launch the rviz MoveIt! plugin, ex:
Without Electric Grippers | $ roslaunch sawyer_moveit_config sawyer_moveit.launch |
With Electric Grippers | $ roslaunch sawyer_moveit_config sawyer_moveit.launch electric_gripper:=true |
The Rviz gui will then open showing Sawyer with interactive markers:
Executing a Simple Motion Plan
You will see the goal state for the motion planning, shown for each plan group in Orange.
You can then move Sawyer's arms to a planning goal by clicking and dragging the arrows (Cartesian) and rings (orientation) of the interactive markers. Kinematic/collision checking is happening simultaneously and will not allow self collisions (links will turn red), or goal states out of the reachable workspace (inability to drag and endpoint/gripper will turn red).
With a valid goal state, and assuming that the robot is in a valid start state, you are now ready to plan and execute a trajectory from your start state to the goal state.
In the bottom left you will the motion planning frame with a tabbed interface to access different tools of the MoveIt! Rviz visualizer.
Please select the Planning tab in this frame.
Click the Plan tab under the Commands field to plan a trajectory from your start state to the goal. You will see this solution executed in Rviz. When you are happy with the planned trajectory, click Execute to run this trajectory on the robot.
Alternatively, if you would like to immediately execute the first plan from your current position to the goal position use the Plan and Execute button.
Another useful field in the Planning tab is Query. You can specify here _Select Start State_ choosing <current>, <random>, and <same as goal>, choosing these options with the _Update_ button. Also, You may Select Goal State by clicking that button. Here again you can choose <current>, <random>, and <same as goal> for the Goal State.
Note: It is dangerous to plan from a start state other than your current joint positions. Please update the Select Start State_option under the Query field to reflect your current position before planning. This can be done by clicking the _Select Start State:_ text, from the drop down menu select <current>, click Update to complete this step. You will now be planning from your current position as the start state
After trajectory execution you will see Sawyer has achieved your specified Goal.
Introducing an Environment Representation for Planning
Select the Scene Object tab from the Motion Planning frame.
We will now create a scene object in a text file to be imported into our environment.
$ roscd sawyer_moveit_config $ mkdir sawyer_scenes $ gedit sawyer_scenes/sawyer_pillar.scene
Copy in the following scene describing a pillar
pillar * pillar 1 box 0.2 0.2 1 0.6 0.15 0 0 0 0 1 0 0 0 0 .
Save and exit.
You can now import this scene from the Scene Geometry field selecting Import From Text
Navigating to select sawyer_moveit_config/sawyer_scenes/sawyer_pillar.scene
After opening this scene you will now see the pillar inserted into your environment.
Important: You must publish your current scene so that MoveIt! knows that it will need to plan around your modified environment. Do so by selecting the Context_ tab from the Motion Planning frame. Under this tab you must click the _Publish Current Scene Button under the Planning Library field.
Similar to our previous planning we can now drag our interactive markers moving the goal state to a location on the opposite side of the pillar.
Selecting the Planning tab in the motion planning frame you can now plan a new trajectory that will avoid collision with your environment object (the pillar). The shell in which you launched sawyer_moveit.launch will provide information regarding which planner will be used, how long it took to find a solution, path simplification/smoothing time, and more. This will also display if your planner was unsuccessful in finding an allowable solution. This is often caused by collision with the environment during testing of the execution or invalid start/goal states. In very constrained or difficult motions, you may have to plan several times to find an acceptable solution for execution.
Upon execution the robot will avoid this 'virtual' object tracking the commanded trajectory.
That's it, you have successfully commanded Sawyer using MoveIt!
Programmatic Interaction for Planning
There is much more information, tutorials, API documentation and more on moveit.ros.org.
Interfaces
ROS APIs
See the API Reference page for details.
- Joint Trajectory Action Server - /robot/limb/right/follow_joint_trajectory [control_msgs/FollowJointTrajectoryAction]
INTERA_INTERFACE APIs
- JointTrajectoryActionServer class:
joint_trajectory_action_server.py
Also see the Full intera_interface API docs for more details
Related Examples/Tutorials
Troubleshooting
The Arm is not Executing the Trajectory
Verify that the robot is enabled:
rosrun intera_interface enable_robot.py -e
Verify that the trajectory controller has been started:
rosrun intera_interface joint_trajectory_action_server.py
Best practice in case of using the Gazebo simulation together with MoveIt will be following command:
rosrun intera_interface joint_trajectory_action_server.py -m position_w_id
Arm not Executing Plan – “Unable to Identify any Set of Controllers”
Problem Description:
Pressed plan, solution was found and a trajectory execution service request was recieved after which I got the error:
Unable to identify any set of controllers that can actuate the specified joints: [right_j0 right_j1 right_j2 right_j3 right_j4 right_j5 right_j6 ]
After which nothing occurred.
If you see the following warning error in the terminal output when roslaunch-ing sawyer_moveit.launch:
[FATAL] [1372432489.342541284]: Parameter '~moveit_controller_manager' not specified. This is needed to identify the plugin to use for interacting with controllers. No paths can be executed.
This indicates you need to make sure you have the appropriate controller manager plugins installed. Make sure to follow the Sawyer MoveIt! Installation instructions and install the required Debian packages for both moveit-full and any required plugins.