Motion Planning Pipeline

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.

Getting Started

If you haven’t already done so, make sure you’ve completed the steps in Getting Started.

Running the Code

Open two shells. In the first shell start RViz and wait for everything to finish loading:

roslaunch panda_moveit_config demo.launch

In the second shell, run the launch file:

roslaunch moveit_tutorials motion_planning_pipeline_tutorial.launch

Note: This tutorial uses the RvizVisualToolsGui panel to step through the demo. To add this panel to RViz, follow the instructions in the Visualization Tutorial.

After a short moment, the RViz window should appear and look similar to the one at the top of this page. To progress through each demo step either press the Next button in the RvizVisualToolsGui panel at the bottom of the screen or select Key Tool in the Tools panel at the top of the screen and then press N on your keyboard while RViz is focused.

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,

The Entire Code

The entire code can be seen here in the MoveIt GitHub project.

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::RobotModelLoaderPtr robot_model_loader(
    new robot_model_loader::RobotModelLoader("robot_description"));

Using the RobotModelLoader, we can construct a planing scene monitor that will create a planning scene, monitors planning scene diffs, and apply the diffs to it’s internal planning scene. We then call startSceneMonitor, startWorldGeometryMonitor and startStateMonitor to fully initialize the planning scene monitor

planning_scene_monitor::PlanningSceneMonitorPtr psm(
    new planning_scene_monitor::PlanningSceneMonitor(robot_model_loader));

/* listen for planning scene messages on topic /XXX and apply them to
                     the internal planning scene accordingly */
psm->startSceneMonitor();
/* listens to changes of world geometry, collision objects, and (optionally) octomaps */
psm->startWorldGeometryMonitor();
/* listen to joint state updates as well as changes in attached collision objects
                      and update the internal planning scene accordingly*/
psm->startStateMonitor();

/* We can also use the RobotModelLoader to get a robot model which contains the robot's kinematic information */
moveit::core::RobotModelPtr robot_model = robot_model_loader->getModel();

/* We can get the most up to date robot state from the PlanningSceneMonitor by locking the internal planning scene
   for reading. This lock ensures that the underlying scene isn't updated while we are reading it's state.
   RobotState's are useful for computing the forward and inverse kinematics of the robot among many other uses */
moveit::core::RobotStatePtr robot_state(
    new moveit::core::RobotState(planning_scene_monitor::LockedPlanningSceneRO(psm)->getCurrentState()));

/* Create a JointModelGroup to keep track of the current robot pose and planning group. The Joint Model
   group is useful for dealing with one set of joints at a time such as a left arm or a end effector */
const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup("panda_arm");

We can now setup the PlanningPipeline object, which will use the ROS parameter 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"));

Visualization

The package MoveItVisualTools provides many capabilities for visualizing objects, robots, and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script.

namespace rvt = rviz_visual_tools;
moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
visual_tools.deleteAllMarkers();

/* Remote control is an introspection tool that allows users to step through a high level script
   via buttons and keyboard shortcuts in RViz */
visual_tools.loadRemoteControl();

/* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/
Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity();
text_pose.translation().z() = 1.75;
visual_tools.publishText(text_pose, "Motion Planning Pipeline Demo", rvt::WHITE, rvt::XLARGE);

/* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */
visual_tools.trigger();

/* We can also use visual_tools to wait for user input */
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo");

Pose Goal

We will now create a motion plan request for the right arm of the Panda 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 = "panda_link0";
pose.pose.position.x = 0.3;
pose.pose.position.y = 0.0;
pose.pose.position.z = 0.75;
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 = "panda_arm";
moveit_msgs::Constraints pose_goal =
    kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle);
req.goal_constraints.push_back(pose_goal);

Before planning, we will need a Read Only lock on the planning scene so that it does not modify the world representation while planning

{
  planning_scene_monitor::LockedPlanningSceneRO lscene(psm);
  /* Now, call the pipeline and check whether planning was successful. */
  planning_pipeline->generatePlan(lscene, req, res);
}
/* Now, call the pipeline and check whether planning was successful. */
/* 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);
visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group);
visual_tools.trigger();

/* Wait for user input */
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");

Joint Space Goals

/* First, set the state in the planning scene to the final state of the last plan */
robot_state = planning_scene_monitor::LockedPlanningSceneRO(psm)->getCurrentStateUpdated(response.trajectory_start);
robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions);
moveit::core::robotStateToRobotStateMsg(*robot_state, req.start_state);

Now, setup a joint space goal

moveit::core::RobotState goal_state(*robot_state);
std::vector<double> joint_values = { -1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0 };
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);

Before planning, we will need a Read Only lock on the planning scene so that it does not modify the world representation while planning

{
  planning_scene_monitor::LockedPlanningSceneRO lscene(psm);
  /* Now, call the pipeline and check whether planning was successful. */
  planning_pipeline->generatePlan(lscene, 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);
visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group);
visual_tools.trigger();

/* Wait for user input */
visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");

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, set the state in the planning scene to the final state of the last plan */
robot_state = planning_scene_monitor::LockedPlanningSceneRO(psm)->getCurrentStateUpdated(response.trajectory_start);
robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions);
moveit::core::robotStateToRobotStateMsg(*robot_state, req.start_state);

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

const moveit::core::JointModel* joint_model = joint_model_group->getJointModel("panda_joint3");
const moveit::core::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);

Before planning, we will need a Read Only lock on the planning scene so that it does not modify the world representation while planning

  {
    planning_scene_monitor::LockedPlanningSceneRO lscene(psm);
    /* Now, call the pipeline and check whether planning was successful. */
    planning_pipeline->generatePlan(lscene, 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);
  visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group);
  visual_tools.trigger();

  /* Wait for user input */
  visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to finish the demo");

  ROS_INFO("Done");
  return 0;
}

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.

Open Source Feedback

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