Motion Planning Pipeline Tutorial

In MoveIt!, the motion planners are setup to plan paths. However, there are often times when we may want to pre-process the motion planning request or post-process the planned path (e.g. for time parameterization). In such cases, we use the planning pipeline which chains a motion planner with pre-processing and post-processing stages. The pre and post-processing stages, called planning request adapters, can be configured by name from the ROS parameter server. In this tutorial, we will run you through the C++ code to instantiate and call such a planning pipeline.

Start

Setting up to start using a planning pipeline is pretty easy. Before we can load the planner, we need two objects, a RobotModel and a PlanningScene. We will start by instantiating a RobotModelLoader object, which will look up the robot description on the ROS parameter server and construct a RobotModel for us to use.

robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr robot_model = robot_model_loader.getModel();

Using the RobotModel, we can construct a PlanningScene that maintains the state of the world (including the robot).

planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));

We can now setup the PlanningPipeline object, which will use the ROS param server to determine the set of request adapters and the planning plugin to use

planning_pipeline::PlanningPipelinePtr planning_pipeline(new planning_pipeline::PlanningPipeline(robot_model, node_handle, "planning_plugin", "request_adapters"));

/* Sleep a little to allow time to startup rviz, etc. */
ros::WallDuration sleep_time(20.0);
sleep_time.sleep();

Pose Goal

We will now create a motion plan request for the right arm of the PR2 specifying the desired pose of the end-effector as input.

planning_interface::MotionPlanRequest req;
planning_interface::MotionPlanResponse res;
geometry_msgs::PoseStamped pose;
pose.header.frame_id = "torso_lift_link";
pose.pose.position.x = 0.75;
pose.pose.position.y = 0.0;
pose.pose.position.z = 0.0;
pose.pose.orientation.w = 1.0;

A tolerance of 0.01 m is specified in position and 0.01 radians in orientation

std::vector<double> tolerance_pose(3, 0.01);
std::vector<double> tolerance_angle(3, 0.01);

We will create the request as a constraint using a helper function available from the kinematic_constraints package.

req.group_name = "right_arm";
moveit_msgs::Constraints pose_goal = kinematic_constraints::constructGoalConstraints("r_wrist_roll_link", pose, tolerance_pose, tolerance_angle);
req.goal_constraints.push_back(pose_goal);

Now, call the pipeline and check whether planning was successful.

planning_pipeline->generatePlan(planning_scene, req, res);
/* Check that the planning was successful */
if(res.error_code_.val != res.error_code_.SUCCESS)
{
  ROS_ERROR("Could not compute plan successfully");
  return 0;
}

Visualize the result

ros::Publisher display_publisher = node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true);
moveit_msgs::DisplayTrajectory display_trajectory;

/* Visualize the trajectory */
ROS_INFO("Visualizing the trajectory");
moveit_msgs::MotionPlanResponse response;
res.getMessage(response);

display_trajectory.trajectory_start = response.trajectory_start;
display_trajectory.trajectory.push_back(response.trajectory);
display_publisher.publish(display_trajectory);

sleep_time.sleep();

Joint Space Goals

/* First, set the state in the planning scene to the final state of the last plan */
robot_state::RobotState& robot_state = planning_scene->getCurrentStateNonConst();
planning_scene->setCurrentState(response.trajectory_start);
const robot_model::JointModelGroup* joint_model_group = robot_state.getJointModelGroup("right_arm");
robot_state.setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions);

Now, setup a joint space goal

robot_state::RobotState goal_state(robot_model);
std::vector<double> joint_values(7, 0.0);
joint_values[0] = -2.0;
joint_values[3] = -0.2;
joint_values[5] = -0.15;
goal_state.setJointGroupPositions(joint_model_group, joint_values);
moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group);

req.goal_constraints.clear();
req.goal_constraints.push_back(joint_goal);

Call the pipeline and visualize the trajectory

planning_pipeline->generatePlan(planning_scene, req, res);
/* Check that the planning was successful */
if(res.error_code_.val != res.error_code_.SUCCESS)
{
  ROS_ERROR("Could not compute plan successfully");
  return 0;
}
/* Visualize the trajectory */
ROS_INFO("Visualizing the trajectory");
res.getMessage(response);
display_trajectory.trajectory_start = response.trajectory_start;
display_trajectory.trajectory.push_back(response.trajectory);

Now you should see two planned trajectories in series

display_publisher.publish(display_trajectory);
sleep_time.sleep();

Using a Planning Request Adapter

A planning request adapter allows us to specify a series of operations that should happen either before planning takes place or after the planning has been done on the resultant path

First, let’s purposefully set the initial state to be outside the joint limits and let the planning request adapter deal with it

/* First, set the state in the planning scene to the final state of the last plan */
robot_state = planning_scene->getCurrentStateNonConst();
planning_scene->setCurrentState(response.trajectory_start);
robot_state.setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions);

Now, set one of the joints slightly outside its upper limit

const robot_model::JointModel* joint_model = joint_model_group->getJointModel("r_shoulder_pan_joint");
const robot_model::JointModel::Bounds& joint_bounds = joint_model->getVariableBounds();
std::vector<double> tmp_values(1, 0.0);
tmp_values[0] = joint_bounds[0].min_position_ - 0.01;
robot_state.setJointPositions(joint_model, tmp_values);
req.goal_constraints.clear();
req.goal_constraints.push_back(pose_goal);

Call the planner again and visualize the trajectories

  planning_pipeline->generatePlan(planning_scene, req, res);
  if(res.error_code_.val != res.error_code_.SUCCESS)
  {
    ROS_ERROR("Could not compute plan successfully");
    return 0;
  }
  /* Visualize the trajectory */
  ROS_INFO("Visualizing the trajectory");
  res.getMessage(response);
  display_trajectory.trajectory_start = response.trajectory_start;
  display_trajectory.trajectory.push_back(response.trajectory);
  /* Now you should see three planned trajectories in series*/
  display_publisher.publish(display_trajectory);

  sleep_time.sleep();
  ROS_INFO("Done");
  return 0;
}

The entire code

The entire code can be seen here in the moveit_pr2 github project.

Compiling the code

Follow the instructions for compiling code from source.

The launch file

The entire launch file is here on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package that you have as part of your MoveIt! setup.

Running the code

Roslaunch the launch file to run the code directly from moveit_tutorials:

roslaunch moveit_tutorials motion_planning_api_tutorial.launch

Expected Output

In Rviz, we should be able to see three trajectories being replayed eventually:

  1. The robot moves its right arm to the pose goal in front of it,
  2. The robot moves its right arm to the joint goal to the side,
  3. The robot moves its right arm back to the original pose goal in front of it,

Open Source Feedback

See something that needs improvement? Please open a pull request on this GitHub page