MoveIt Tutorial

From sdk-wiki
Revision as of 14:10, 25 June 2014 by Csmith (Talk | contribs)

Jump to: navigation, search

MoveIt! Logo
MoveIt! Please visit the MoveIt! homepage for more information


This tutorial describes how to use the Baxter Research Robot with MoveIt! the standard ROS motion planning framework.


This tutorial requires a ROS distribution >= Groovy

Check out the Baxter MoveIt configuration package into your ROS workspace (follow Catkin or rosbuild tab instructions accordingly)]

    $ cd ~/ros_ws/src
    $ git clone

The follow debian packages are required for using MoveIt! with Baxter

    = Make sure to update your sources =
    $ sudo apt-get update
    = Install MoveIt! =
    $ sudo apt-get install ros-groovy-moveit-full

Run catkin_make to make the new additions to your ROS workspace

    $ cd ~/ros_ws/
    $ ./
    $ catkin_make


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!

Baxter now supports using MoveIt! through the addition of the configurable joint trajectory action server, and hosting of the necessary MoveIt! configuration files on ros_planning/moveit_robots.

This tutorial will focus on the MoveIt! Rviz plugin as an introduction to some of the capabilities of MoveIt!

Baxter Planning Groups

Describes the joints considered during motion planning. These are specified in the SRDF SRDF for Baxter. Baxter's SRDF includes planning groups, additional collision checking information, and default configurations.

Planning Groups

  • both_arms
    • left_arm
    • right_arm
  • left_arm
    • left_s0
    • left_s1
    • left_e0
    • left_e1
    • left_w0
    • left_w1
    • left_w2
    • left_hand
    • left_endpoint
  • right_arm
    • right_s0
    • right_s1
    • right_e0
    • right_e1
    • right_w0
    • right_w1
    • right_w2
    • right_hand
    • right_endpoint
  • left_hand
    • left_gripper
  • right_hand
    • right_gripper

You can view the SRDF at any time:

    $ rosed baxter_moveit_config baxter.srdf



Verify that the robot is enabled from an RSDK terminal session, ex:

    $ rosrun baxter_tools -e

Start the joint trajectory controller, ex:

 $ rosrun baxter_interface

In another RSDK terminal session, Launch the rviz MoveIt! plugin, ex:

    $ roslaunch baxter_moveit_config demo_baxter.launch

Note:* Do not launch baxter_moveit_config demo_sim.launch with the ROS_MASTER_URI set to the robot (ie. using the robot's ros master) as this starts a new joint_state_publisher/robot_state_publisher causing the robot's internal joint_state_publisher/robot_state_publisher be preempted, essentially ceasing Baxter's ability to move the arms until reboot. *Please use baxter_moveit_config demo_baxter.launch to run this demonstration on Baxter.

The Rviz gui will then open showing Baxter with interactive markers:
Baxter MoveIt rviz start

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 Baxter'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).

Baxter MoveIt rviz interact

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.

MoveIt planning tab

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 Baxter has achieved your specified Goal.
MoveIt planning done

Introducing an environment representation for planning

Select the Scene Object tab from the Motion Planning frame.

MoveIt planning scene object tab

We will now create a scene object in a text file to be imported into our environment.

 $ roscd baxter_moveit_config
 $ mkdir baxter_scenes
 $ gedit baxter_scenes/baxter_pillar.scene

Copy in the following scene describing a pillar

 * pillar
 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 baxter_moveit_config/baxter_scenes/baxter_pillar.scene

After opening this scene you will now see the pillar inserted into your environment.

Baxter MoveIt Pillar

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.

MoveIt Context Tab

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.

MoveIt Context Tab

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 demo_baxter.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.

Baxter Pillar Done

That's it, you have successfully commanded Baxter using MoveIt!

There is much more information, tutorials, API documentation and more on

MoveIt! C++ Example

MoveIt! Python - MoveIt Commander

MoveIt! API


It's possible to integrate sensor data from the kinect with MoveIt! so that you can plan paths for Baxter in dynamic environments. This is new functionality, so you should first update to the latest. MoveIt configuration package At this time, there are no drivers available to integrate either linux or ROS with the Xbox One Kinect, or the K4W2, so these instructions are for the original Xbox kinect, or the K4W. To get the kinect working, we first need to install the OpenNI ros packages

  $ sudo apt-get install ros-groovy-openni-camera ros-groovy-openni-launch

In an RSDK shell, launch the openni drivers to check that they're working correctly.

  $ roslaunch openni_launch openni.launch

In a separate RSDK shell, you can use image_view to look at the data

  $ rosrun image_view disparity_view image:=/camera/depth/disparity

You can also just look at the rgb image

  $ rosrun image_view image_view image:=/camera/rgb/image_color

RGB and Depth images from kinect

If this all works, then you should be good to go!

Integrating with MoveIt!

You'll probably first want to specify where you've placed your kinect relative to Baxter. We set up a static transform publisher in our MoveIt! launch files to do this for us. By default, the camera is set to position:

 #  x y z yaw pitch roll parent_frame
 #  1 0 0  0    0     0     /torso

If you're fine with this location for now, you can leave it as is. If not, you can edit the file

  $ rosed baxter_moveit_config baxter_moveit_sensor_manager.launch

where you can update the location of your kinect by changing the arguments at

  <node pkg="tf" type="static_transform_publisher" name="camera_link_broadcaster"
  args="1.0 0.0 0.0 0.0 0.0 0.0 /torso /camera_link 100" />

More information on this transform publisher can be found on ROS's wiki

After doing this, you can run MoveIt! using input from the kinect. You should not be running your own OpenNI server anymore, but you should have the joint trajectory action server running in an RSDK shell. In another RSDK shell, run the kinect demo:

  $ roslaunch baxter_moveit_config demo_kinect.launch

Alternatively, you could run the regular MoveIt! demo and pass in a kinect argument

  $ roslaunch baxter_moveit_config demo_baxter.launch kinect:=true

After launching rviz, you should be able to see the input data from your kinect sensor in the environment. Self-filtering should be performed for you to ensure that the kinect doesn't consider Baxter to be part of the planning environment. You can now do motion planning for Baxter using the kinect data.
A motion plan for Baxter with input from the kinect
Another motion plan for Baxter with the kinect
The floating set of axes in the images shows the camera location


If you want to use the kinect data with our MoveIt! simulator, that's also possible. Be careful not to run the simulator in an RSDK shell, or with the ROS_MASTER_URI set to the robot

  $ roslaunch baxter_moveit_config demo_sim.launch kinect:=true


There are a couple of settings that you may want to adjust for your use case, which can be done through the kinect yaml file

  rosed baxter_moveit_config kinect_sensor.yaml

Where you'll see the following information

 - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
   point_cloud_topic: /move_group/camera/depth/points
   max_range: 5.0
   padding_offset: 0
   padding_scale: 3.0
   frame_subsample: 1
   point_subsample: 1

Information about these settings can be found on the MoveIt! wiki


#ikfast IKFast provides analytical closed-form solutions for manipulator inverse kinematics. Part of the OpenRAVE robot architecture/software framework, IKFast has been used to provide closed-form solutions for Baxter's inverse kinematics.

Advantages include order of magnitude faster IK solutions and the ability explore the manipulator's null space!

Using Baxter's MoveIt! IKFast plugins

In the baxter_moveit_config package - modify the kinematics.yaml file to specify the use of the IKFast plugins.

 rosed baxter_moveit_config kinematics.yaml

You can now uncomment the use of the IKFastKinematicsPlugin, commenting out the default KDL solver.

The result should look like so:

 # kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
 # uncomment to use ikfast kinematics plugin
 kinematics_solver: baxter_left_arm_kinematics/IKFastKinematicsPlugin
 kinematics_solver_attempts: 3
 kinematics_solver_search_resolution: 0.005
 kinematics_solver_timeout: 0.005
 # kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
 # uncomment to use ikfast kinematics plugin
 kinematics_solver: baxter_right_arm_kinematics/IKFastKinematicsPlugin
 kinematics_solver_attempts: 3
 kinematics_solver_search_resolution: 0.005
 kinematics_solver_timeout: 0.005

You will now need to recompile and install the IKFast plugins.

   catkin_make install --pkg baxter_ikfast_right_arm_plugin
   catkin_make install --pkg baxter_ikfast_left_arm_plugin

Note: It is known that with 0.6 software the SDK will prevent users from executing: ``catkin_make install`` across the entire workspace. This will be addressed with the upcoming release.

That's it! MoveIt! will now be using IKFast as it's kinematics solver!

Please try it out following the above tutorial.



See the API Reference page for details.

  • Joint Trajectory Action Server - /robot/limb/right/follow_joint_trajectory [control_msgs/FollowJointTrajectoryAction]
  • Joint Trajectory Action Server - /robot/limb/left/follow_joint_trajectory [control_msgs/FollowJointTrajectoryAction]

baxter_interface APIs

  • JointTrajectoryActionServer class:

Related Examples/Tutorials


The arm is not executing the trajectory

Verify that the robot is enabled:

rosrun tools -e

Verify that the trajectory controller has been started:

rosrun baxter_interface

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: [left_e0 left_e1 left_s0 left_s1 left_w0 left_w1 left_w2 right_e0 right_e1 right_s0 right_s1 right_w0 right_w1 right_w2 ]
After which nothing occurred.

If you see the following warning error in the terminal output when roslaunch-ing demo_baxter.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 Baxter MoveIt! Installation instructions and install the required debian packages for both moveit-full and any required plugins. (For the current version, yes - you do need to install ros-groovy-pr2-moveit-plugins, even though it is not a pr2 - these plugins include default versions which enable the interface to the controllers.)