How to Add and Plan Around Objects Using MoveIt 2

In this tutorial, we will build upon our previous “Hello World” project to learn how to plan around objects in a simulated environment using C++ and MoveIt 2. I will guide you through the process of inserting collision objects into the planning scene and programming the robot to plan its movements while avoiding these obstacles.

The official instructions for this tutorial are available on the MoveIt 2 website, but we’ll walk through everything together, step by step. We’ll cover how to create and add collision objects to the scene, update target poses, and use the Planning Scene Interface to communicate changes to MoveGroup.

By the end of this tutorial, you will be able to create a program that allows a robot to plan and execute movements while avoiding obstacles in its environment. The result will look something like this:

planning-around-objects-moveit

Prerequisites

All my code for this project is located here on GitHub.

Add moveit_visual_tools as a Dependency

First let’s add moveit_visual_tools as a dependency inside the hello_moveit package.

The moveit_visual_tools package is a visualization toolkit for MoveIt that provides tools to visualize robot states, trajectories, collision objects, and planning scenes in ROS 2. It integrates with RViz and is particularly useful for debugging motion planning issues, offering functions to generate markers, display text, and visualize trajectories in the 3D environment.

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/
gedit package.xml

Add this dependency:

<depend>moveit_visual_tools</depend>

Save the file, and close it.

gedit CMakeLists.txt

Add this:

find_package(moveit_visual_tools REQUIRED)

ament_target_dependencies(
  moveit_ros_planning_interface
  moveit_visual_tools
  rclcpp
)

Save the file, and close it.

Now let’s build the package.

cd ~/ros2_ws/
rosdep install --from-paths src --ignore-src -y

You will see a prompt to install moveit-visual-tools.

1-prompt-install-moveit-visual-tools

Type your password, and press Enter.

I got an error that the ros-<ros_distro>-warehouse-ros-mongo package wasn’t found. Don’t worry about it.

colcon build
source ~/.bashrc

Create a New File

We’ll start our tutorial by creating a new C++ source file in the appropriate directory of our ROS 2 workspace. Here’s how to do it…

Open a terminal window on your computer. Navigate to the correct directory in your ROS 2 workspace by entering this command:

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/src

Now that we’re in the right location, let’s create our new file. We’ll name it “plan_around_objects.cpp”. You can create this file using a text editor of your choice. For example, if you’re using the gedit text editor, you would type:

gedit plan_around_objects.cpp

With our new file open, add this code:

/**
 * @file plan_around_objects.cpp
 * @brief Demonstrates basic usage of MoveIt with ROS 2 and collision avoidance.
 *
 * This program initializes a ROS 2 node, sets up a MoveIt interface for a robot manipulator,
 * creates a collision object in the scene, plans a motion to a target pose while avoiding
 * the collision object, and executes the planned motion.
 *
 * @author Addison Sears-Collins
 * @date August 8, 2024
 */

#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit_visual_tools/moveit_visual_tools.h>

#include <geometry_msgs/msg/pose_stamped.hpp>

#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <thread>

/**
 * @brief The main function that starts our program.
 *
 * This function sets up our ROS 2 environment and prepares it for robot control.
 *
 * @param argc The number of input arguments our program receives.
 * @param argv The list of input arguments our program receives.
 * @return int A number indicating if our program finished successfully (0) or not.
 */
int main(int argc, char * argv[])
{
  // Start up ROS 2
  rclcpp::init(argc, argv);
  
  // Creates a node named "plan_around_objects". The node is set up to automatically
  // handle any settings (parameters) we might want to change later without editing the code.
  auto const node = std::make_shared<rclcpp::Node>(
    "plan_around_objects",
    rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)
  );

  // Creates a "logger" that we can use to print out information or error messages
  // as our program runs.
  auto const logger = rclcpp::get_logger("plan_around_objects");
  
  // This code creates a separate thread, which is like a mini-program running alongside our main program. 
  // This thread uses a ROS 2 "executor" to continuously process information about the robot's state. 
  // By running this in its own thread, our ROS 2 node can keep getting updates about the robot without 
  // interrupting the main flow of our program.
  rclcpp::executors::SingleThreadedExecutor executor;
  executor.add_node(node);
  auto spinner = std::thread([&executor]() { executor.spin(); });

  // Create the MoveIt MoveGroup Interfaces
  // These interfaces are used to plan and execute movements, set target poses,
  // and perform other motion-related tasks for each respective part of the robot.
  // The use of auto allows the compiler to automatically deduce the type of variable.
  // Source: https://github.com/moveit/moveit2/blob/main/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h
  using moveit::planning_interface::MoveGroupInterface;
  auto arm_group_interface = MoveGroupInterface(node, "arm");

  // Specify a planning pipeline to be used for further planning 
  arm_group_interface.setPlanningPipelineId("ompl");
  
  // Specify a planner to be used for further planning
  arm_group_interface.setPlannerId("RRTConnectkConfigDefault");  

  // Specify the maximum amount of time in seconds to use when planning
  arm_group_interface.setPlanningTime(1.0);
  
  // Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1].
  arm_group_interface.setMaxVelocityScalingFactor(1.0);
  
  //  Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1].
  arm_group_interface.setMaxAccelerationScalingFactor(1.0);

  // Display helpful logging messages on the terminal
  RCLCPP_INFO(logger, "Planning pipeline: %s", arm_group_interface.getPlanningPipelineId().c_str());    
  RCLCPP_INFO(logger, "Planner ID: %s", arm_group_interface.getPlannerId().c_str());
  RCLCPP_INFO(logger, "Planning time: %.2f", arm_group_interface.getPlanningTime());
  
  // Construct and initialize MoveItVisualTools
  auto moveit_visual_tools =
      moveit_visual_tools::MoveItVisualTools{ node, "base_link", rviz_visual_tools::RVIZ_MARKER_TOPIC,
                                              arm_group_interface.getRobotModel() };
											  
  // Erase all existing visual markers from the RViz visualization. 
  moveit_visual_tools.deleteAllMarkers();

  // Load the remote control interface for MoveIt visual tools. 
  moveit_visual_tools.loadRemoteControl();
  
  // Lambda function to draw a title in the RViz visualization
  auto const draw_title = [&moveit_visual_tools](auto text) {
    // Nested lambda to create a pose for the text
    auto const text_pose = [] {
        // Create an identity transform
        auto msg = Eigen::Isometry3d::Identity();
        // Set the z-coordinate to 1.0 (1 meter above the origin)
        msg.translation().z() = 1.0;
        return msg;
    }();
    
    // Publish the text to RViz
    // Parameters: pose, text content, color (WHITE), and size (XLARGE)
    moveit_visual_tools.publishText(text_pose, text, rviz_visual_tools::WHITE, rviz_visual_tools::XLARGE);
  };
 
  // Lambda function to display a prompt message in RViz
  auto const prompt = [&moveit_visual_tools](auto text) { 
    moveit_visual_tools.prompt(text); 
  };

  // Lambda function to visualize a trajectory as a line in RViz
  auto const draw_trajectory_tool_path = 
    [&moveit_visual_tools, jmg = arm_group_interface.getRobotModel()->getJointModelGroup("arm")](
	  auto const trajectory) {moveit_visual_tools.publishTrajectoryLine(trajectory, jmg);};

  // Set a target pose for the end effector of the arm 
  auto const arm_target_pose = [&node]{
    geometry_msgs::msg::PoseStamped msg;
    msg.header.frame_id = "base_link";
    msg.header.stamp = node->now(); 
    msg.pose.position.x = 0.128;
    msg.pose.position.y = -0.266;
    msg.pose.position.z = 0.111;
    msg.pose.orientation.x = 0.635;
    msg.pose.orientation.y = -0.268;
    msg.pose.orientation.z = 0.694;
    msg.pose.orientation.w = 0.206;
    return msg;
  }();
  arm_group_interface.setPoseTarget(arm_target_pose);
  
  // Create collision object for the robot to avoid
  auto const collision_object = [frame_id = arm_group_interface.getPlanningFrame(), &node, &logger] {
  
    // Print the planning frame for debugging purposes
    RCLCPP_INFO(logger, "Planning frame: %s", frame_id.c_str());

    // Initialize a CollisionObject message
    moveit_msgs::msg::CollisionObject collision_object;
  
    // Set the frame ID for the collision object
    collision_object.header.frame_id = frame_id;
  
    // Set the timestamp to the current time
    collision_object.header.stamp = node->now();
  
    // Assign a unique ID to the collision object
    collision_object.id = "box1";

    // Define the shape of the collision object as a box
    shape_msgs::msg::SolidPrimitive primitive;
    primitive.type = primitive.BOX;
    primitive.dimensions.resize(3);
  
    // Set the dimensions of the box (in meters)
    primitive.dimensions[primitive.BOX_X] = 0.2;  // Width
    primitive.dimensions[primitive.BOX_Y] = 0.05;  // Depth
    primitive.dimensions[primitive.BOX_Z] = 0.50;  // Height

    // Define the pose (position and orientation) of the box
    geometry_msgs::msg::Pose box_pose;
  
    // Set the position of the box center
    box_pose.position.x = 0.22;  // meters in x-direction
    box_pose.position.y = 0.0;   // Centered in y-direction
    box_pose.position.z = 0.25;  // meters in z-direction
  
    // Set the orientation of the box (no rotation in this case)
    box_pose.orientation.x = 0.0;
    box_pose.orientation.y = 0.0;
    box_pose.orientation.z = 0.0;
    box_pose.orientation.w = 1.0;

    // Add the shape and pose to the collision object
    collision_object.primitives.push_back(primitive);
    collision_object.primitive_poses.push_back(box_pose);
  
    // Set the operation to add the object to the planning scene
    collision_object.operation = collision_object.ADD;

    // Log information about the created collision object
    RCLCPP_INFO(logger, "Created collision object: %s", collision_object.id.c_str());
	
    RCLCPP_INFO(logger, "Box dimensions: %.2f x %.2f x %.2f", 
      primitive.dimensions[primitive.BOX_X],
      primitive.dimensions[primitive.BOX_Y],
      primitive.dimensions[primitive.BOX_Z]);
	  
    RCLCPP_INFO(logger, "Box position: (%.2f, %.2f, %.2f)",
      box_pose.position.x, box_pose.position.y, box_pose.position.z);

    // Return the fully defined collision object
    return collision_object;
  }();
  
  // Set up a virtual representation of the robot's environment
  moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
  
  // Add an object to this virtual environment that the robot needs to avoid colliding with
  planning_scene_interface.applyCollisionObject(collision_object);
  
  // Ask the user to press 'next' to continue
  prompt("Press 'next' in the RvizVisualToolsGui window to plan");
  
  // Set up a title for the next visualization step
  draw_title("Planning");
  
  // Update the visualization to show the new title and wait for user input
  moveit_visual_tools.trigger();

  // Create a plan to that target pose
  // This will give us two things:
  // 1. Whether the planning was successful (stored in 'success')
  // 2. The actual motion plan (stored in 'plan')
  auto const [success, plan] = [&arm_group_interface] {
    moveit::planning_interface::MoveGroupInterface::Plan msg;
    auto const ok = static_cast<bool>(arm_group_interface.plan(msg));
    return std::make_pair(ok, msg);
  }();

  // Try to execute the movement plan if it was created successfully
  // If the plan wasn't successful, report an error
  // Execute the plan
  if (success)
  {
	// Visualize the planned trajectory in RViz
    draw_trajectory_tool_path(plan.trajectory);
	
    // Trigger the visualization update
    moveit_visual_tools.trigger();
	
    // Prompt the user to continue to execution
    prompt("Press 'next' in the RvizVisualToolsGui window to execute");
	
    // Update the title in RViz to show we're executing the plan
    draw_title("Executing");
	
    // Trigger another visualization update
    moveit_visual_tools.trigger();
	
    // Execute the planned motion
    arm_group_interface.execute(plan);
  }
  else
  {
    // If planning failed, update the title in RViz
    draw_title("Planning Failed!");
	
    // Trigger the visualization update
    moveit_visual_tools.trigger();
	
    // Log an error message
    RCLCPP_ERROR(logger, "Planning failed!");
  }
  
  // Clean up and shut down the ROS 2 node
  rclcpp::shutdown();
  
  // Wait for the spinner thread to finish
  spinner.join();
  
  // Exit the program
  return 0;
}

Save the file, and close it.

Understanding the Plan Around Objects Code

Let’s walk through the code before we see it in action.

The code starts with some introductory comments explaining what the program does. 

Next, we see a bunch of include statements. These include statements tell the program which tools it needs to use. In this case, it’s bringing in libraries for controlling the robot, planning movements, and visualizing what’s happening.

The main function is where the actual program starts. It begins by initializing ROS 2.

The code sets up a separate thread, which is like a mini-program running alongside our main one. This thread keeps track of what’s happening with the robot in real-time.

Next, it creates interfaces for controlling the robot arm. These interfaces are how our program talks to the robot, telling it where to move and how to plan its movements. The code specifies some settings for these movements, like how fast the arm can move and how long it can take to plan a path.

The program then sets up tools for visualizing what’s happening. This allows us to see a 3D representation of the robot and its planned movements in RViz.

After that, the code specifies a target pose for the robot arm. This is the position and orientation we want the arm to move to.

One of the key parts of this program is creating a virtual obstacle. It defines a box in the robot’s workspace that the arm needs to avoid. This box is given a specific size and position.

With the target and obstacle set up, the program then asks the robot to plan a path to the target that avoids the obstacle. If it successfully creates a plan, it shows this plan in RViz and then tells the robot to execute the movement.

Throughout this process, the code includes various prompts and visual cues to keep you informed about what’s happening. It also has error handling to deal with situations where the robot can’t find a safe path to the target.

Finally, the program cleans up after itself, shutting down ROS 2 and ending the separate thread it created at the beginning.

Understanding Virtual Joints

One more topic before we run our code. Let’s discuss virtual joints. 

If you look at my code, you will see the following call:

move_group_interface.getPlanningFrame()

This code retrieves the parent frame of the “virtual joint” defined in the SRDF file. In our case, this is the “world” frame.

A virtual joint is like an imaginary connection between your robot and the world around it. It’s not a real, physical joint, but rather a way to tell the robot how it can move in relation to its environment.

Think of it like this: Imagine you have a toy robot on a table. The robot itself can move its arms and legs, but it can also slide around on the table. The sliding motion isn’t due to any actual joint in the robot, but you need a way to describe this movement. That’s where a virtual joint comes in.

For a mobile manipulator, you will often see the following in an SRDF:

<virtual_joint name="virtual_joint" type="planar" parent_frame="odom" child_link="base_footprint" />

odom” is used as the world frame because it represents the robot’s odometry – essentially, its position in the world as the robot understands it based on its movement.

base_footprint” is often chosen as the child link because it represents the base of the robot – imagine the point where the robot touches the ground.

The planar virtual joint tells MoveIt that the robot’s base can move in a plane. It doesn’t actually move the robot, but allows MoveIt to consider the base’s potential positions when planning arm movements.

Also, remember that MoveIt maintains a planning scene that includes the robot’s current state and the environment.

The virtual joint allows the planning scene to be updated with base movements, even though MoveIt isn’t controlling the base directly.

I will also note that for a mobile manipulator, the URDF describes just the physical structure of the robot. It does not include the virtual joint information. The URDF would typically start with the base_footprint link and describe the physical joints and links from there.

The SRDF is where the virtual joint is defined for use with MoveIt. It adds semantic information on top of the URDF, including things like virtual joints, group definitions, and end effectors (i.e. grippers).

Edit CMakeLists.txt

Now let’s build our code.

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/
gedit CMakeLists.txt

Add this code.

Save the file, and close it.

Edit package.xml

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/
gedit package.xml

Add this code.

Save the file, and close it.

Build the Package

cd ~/ros2_ws
colcon build 
source ~/.bashrc

Run the Program

Now that we’ve set up our target pose and added a collision object to the planning scene, it’s time to run our program and see the results.

ros2 launch mycobot_gazebo mycobot_280_arduino_bringup_ros2_control_gazebo.launch.py use_rviz:=false

Launch MoveIt and RViz.

ros2 launch mycobot_moveit_config_manual_setup move_group.launch.py

Run your node:

ros2 run hello_moveit plan_around_objects

When you run the program, you should observe the following in RViz:

  • The robot model should be visible.
  • A box representing your collision object should appear in the planning scene.
2-collision-object

Now click Next under RVizVisualToolsGui on the bottom-left of RViz.

3-click-next

The robot should plan a path to the target pose you specified, avoiding the collision object.

If the planning is successful, you’ll see a visualization of the planned path in RViz. The path should clearly avoid the collision object you added.

You will also see a “Planning request complete!” message in the logs.

4-planning-request-complete

If you don’t see the collision object or if the robot’s planned path seems to ignore it, double-check that your collision object’s dimensions and position are appropriate for your robot’s workspace.

Now type Next again to execute.

You should see your robot move to the goal.

5-robot-reached-the-goal-successfully-moveit-rviz
6-execution-success

That’s it. Keep building!

How to Create Your First C++ MoveIt 2 Project

In this tutorial, we will create a basic “Hello World” project to get your feet wet with C++ and MoveIt 2. I will show you how to move the end of the robotic arm (where the gripper is located) to a desired position and orientation. 

The official instructions are on this page, but we will walk through everything together, step by step.

By the end of this tutorial, you will be able to create this:

hello-world-cpp-moveit2

Prerequisites

All my code for this project is located here on GitHub.

Create a Package

Let’s start by creating a new package for our project. Open a terminal and navigate to the mycobot_ros2 directory in your ROS 2 workspace:

cd ~/ros2_ws/src/mycobot_ros2/

Now, let’s create a new package using the ROS 2 command line tools:

ros2 pkg create --build-type ament_cmake --dependencies moveit_ros_planning_interface rclcpp --node-name hello_moveit_v1 --license BSD-3-Clause hello_moveit

This command creates a new package named “hello_moveit” with the necessary dependencies and a node named “hello_moveit_v1”. The package will be created inside the mycobot_ros2 directory.

Next, let’s move into our newly created package:

cd hello_moveit

Create a ROS Node and Executor

Now that we have our package in place, let’s set up our C++ file to work with MoveIt 2. We’ll start by editing the main source file.

Open the new source code file you created.

cd src
gedit hello_moveit_v1.cpp

Replace the existing content with the following code:

/**
 * @file hello_moveit_v1.cpp
 * @brief A simple program that sets up a ROS 2 node to work with MoveIt for robot control.
 *
 * This program creates a basic setup for controlling a robot using ROS 2 and MoveIt.
 * It doesn't actually move the robot yet, but it prepares everything we need to start
 * planning robot movements in future steps.
 *
 * @author Addison Sears-COllins
 * @date August 07, 2024
 */

#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>

/**
 * @brief The main function that starts our program.
 *
 * This function sets up our ROS 2 environment and prepares it for robot control.
 *
 * @param argc The number of input arguments our program receives.
 * @param argv The list of input arguments our program receives.
 * @return int A number indicating if our program finished successfully (0) or not.
 */
int main(int argc, char * argv[])
{
  // Start up ROS 2
  rclcpp::init(argc, argv);
  
  // Creates a node named "hello_moveit". The node is set up to automatically
  // handle any settings (parameters) we might want to change later without editing the code.
  auto const node = std::make_shared<rclcpp::Node>(
    "hello_moveit",
    rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)
  );

  // Creates a "logger" that we can use to print out information or error messages
  // as our program runs.
  auto const logger = rclcpp::get_logger("hello_moveit");

  // We'll add code here later to actually plan robot movements
  RCLCPP_INFO(logger, "We'll add code here later to actually plan robot movements");

  // Shut down ROS 2 cleanly when we're done
  rclcpp::shutdown();
  return 0;
}

This code sets up the basic structure we need to work with MoveIt 2. It initializes ROS 2, creates a node, sets up logging, and creates a MoveGroupInterface for our robot’s arm.

Let’s compile our code to make sure everything is set up correctly. Go back to your workspace directory:

cd ~/ros2_ws

To build the package with debug information, we’ll use the following command:

colcon build --packages-select hello_moveit

This command builds only our hello_moveit package.

After the build completes successfully, open a new terminal and source your workspace:

source ~/.bashrc

Now you can run your program:

ros2 run hello_moveit hello_moveit_v1

At this point, the program should run and exit without any errors, though it won’t perform any robot movements yet. This step simply confirms that our basic setup is working correctly.

1-add-code-later

Plan and Execute Using MoveGroupInterface

Now that we’ve confirmed our basic setup is working, let’s add the code to plan and execute a motion for our robotic arm. 

Create a new file called hello_moveit_v2.cpp

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/src
gedit hello_moveit_v2.cpp

Add the following code:

/**
 * @file hello_moveit_v2.cpp
 * @brief A simple ROS 2 and MoveIt 2 program to control a robot arm
 *
 * This program demonstrates how to use ROS 2 and MoveIt 2 to control a robot arm.
 * It sets up a node, creates a MoveGroupInterface for the arm, sets a target pose for the gripper_base,
 * plans a trajectory, and executes the planned motion.
 *
 * @author Addison Sears-Collins
 * @date August 07, 2024
 */

#include <geometry_msgs/msg/pose_stamped.hpp>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>

/**
 * @brief The main function that starts our program.
 *
 * This function sets up our ROS 2 environment and prepares it for robot control.
 *
 * @param argc The number of input arguments our program receives.
 * @param argv The list of input arguments our program receives.
 * @return int A number indicating if our program finished successfully (0) or not.
 */
int main(int argc, char * argv[])
{
  // Start up ROS 2
  rclcpp::init(argc, argv);
  
  // Creates a node named "hello_moveit". The node is set up to automatically
  // handle any settings (parameters) we might want to change later without editing the code.
  auto const node = std::make_shared<rclcpp::Node>(
    "hello_moveit",
    rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)
  );

  // Creates a "logger" that we can use to print out information or error messages
  // as our program runs.
  auto const logger = rclcpp::get_logger("hello_moveit");

  // Create the MoveIt MoveGroup Interfaces
  // These interfaces are used to plan and execute movements, set target poses,
  // and perform other motion-related tasks for each respective part of the robot.
  // The use of auto allows the compiler to automatically deduce the type of variable.
  // Source: https://github.com/moveit/moveit2/blob/main/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h
  using moveit::planning_interface::MoveGroupInterface;
  auto arm_group_interface = MoveGroupInterface(node, "arm");

  // Specify a planning pipeline to be used for further planning 
  arm_group_interface.setPlanningPipelineId("ompl");
  
  // Specify a planner to be used for further planning
  arm_group_interface.setPlannerId("RRTConnectkConfigDefault");  

  // Specify the maximum amount of time in seconds to use when planning
  arm_group_interface.setPlanningTime(1.0);
  
  // Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1].
  arm_group_interface.setMaxVelocityScalingFactor(1.0);
  
  //  Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1].
  arm_group_interface.setMaxAccelerationScalingFactor(1.0);

  // Display helpful logging messages on the terminal
  RCLCPP_INFO(logger, "Planning pipeline: %s", arm_group_interface.getPlanningPipelineId().c_str());    
  RCLCPP_INFO(logger, "Planner ID: %s", arm_group_interface.getPlannerId().c_str());
  RCLCPP_INFO(logger, "Planning time: %.2f", arm_group_interface.getPlanningTime());

  // Set a target pose for the end effector of the arm 
  auto const arm_target_pose = [&node]{
    geometry_msgs::msg::PoseStamped msg;
    msg.header.frame_id = "base_link";
    msg.header.stamp = node->now(); 
    msg.pose.position.x = 0.061;
    msg.pose.position.y = -0.176;
    msg.pose.position.z = 0.168;
    msg.pose.orientation.x = 1.0;
    msg.pose.orientation.y = 0.0;
    msg.pose.orientation.z = 0.0;
    msg.pose.orientation.w = 0.0;
    return msg;
  }();
  arm_group_interface.setPoseTarget(arm_target_pose);

  // Create a plan to that target pose
  // This will give us two things:
  // 1. Whether the planning was successful (stored in 'success')
  // 2. The actual motion plan (stored in 'plan')
  auto const [success, plan] = [&arm_group_interface] {
    moveit::planning_interface::MoveGroupInterface::Plan msg;
    auto const ok = static_cast<bool>(arm_group_interface.plan(msg));
    return std::make_pair(ok, msg);
  }();

  // Try to execute the movement plan if it was created successfully
  // If the plan wasn't successful, report an error
  // Execute the plan
  if (success)
  {
    arm_group_interface.execute(plan);
  }
    else
  {
    RCLCPP_ERROR(logger, "Planning failed!");
  }
  
  // Shut down ROS 2 cleanly when we're done
  rclcpp::shutdown();
  return 0;
}

This code does the following:

  1. Sets a target pose for the end effector (gripper_base) of the robotic arm.
  2. Plans a path to reach that target pose.
  3. Executes the plan if it was successful, or logs an error if planning failed.

Now, let’s build our updated code.

Go to CMakeLists.txt

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit/
gedit CMakeLists.txt

Update the file with the hello_moveit_v2.cpp code.

Save the file, and close it.

cd ~/ros2_ws
colcon build
source ~/.bashrc

Launch the controller and Gazebo:

ros2 launch mycobot_gazebo mycobot_280_arduino_bringup_ros2_control_gazebo.launch.py use_rviz:=false

Start the MoveGroup with RViz.

ros2 launch mycobot_moveit_config_manual_setup move_group.launch.py

In another terminal, run your program to move the robotic arm from one place to another:

ros2 run hello_moveit hello_moveit_v2
2-run-hello-moveit

You can safely ignore this warning:

[moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!

If everything is set up correctly, you should see the robot’s gripper move in RViz to the specified pose.

3-robot-at-goal

You can confirm the gripper is in the correct pose by typing the following command and comparing it to the pose you set in your hello_moveit_v2.cpp file.

ros2 run tf2_ros tf2_echo base_link gripper_base

Note: If you run the hello_moveit_v2 node without first launching the demo launch file, it will wait for 10 seconds and then exit with an error message. This is because the MoveGroupInterface looks for a node publishing the robot description topic, which is provided by the demo launch file.

Let’s break down the key components of our hello_moveit_v2.cpp file to understand how it works with MoveIt 2 for controlling the arm.

MoveGroupInterface Creation:

This part sets up a control interface for the robot’s arm. It’s like creating a special remote control that lets us send commands to move the arm.

Setting the Target Pose:

Here, we’re telling the arm where we want it to go. 

Planning the Motion:

This is where the robot figures out how to move from its current position to the target we set. It’s like planning a route on a map – the robot calculates all the steps needed to get from point A to point B safely.

Executing the Plan:

Finally, if the planning was successful, we tell the robot to actually perform the movement we planned. If the planning failed for some reason, we just report an error instead of trying to move.

These steps work together to allow us to control the robot arm in a safe and precise manner, moving it to exactly where we want it to go.

That’s it! Keep building.

How to Configure MoveIt 2 for a Simulated Robot Arm

In the previous tutorial, you learned how to leverage ROS 2 Control to move the robotic arm manually by sending raw joint commands to the robot. This exercise is great for learning, but it is not how things are done in a real-world robotics project.

In this tutorial, I will show you how to set up a ROS 2 software called MoveIt 2 to send those commands. MoveIt 2 is a powerful and flexible motion planning framework for robotic manipulators.

Using MoveIt 2 instead of sending manual commands through a terminal window allows for more sophisticated, efficient, and safer motion planning, taking into account obstacles, joint limits, and other constraints automatically.

By the end of this tutorial, you will be able to create this:

moveit-2-animation-mycobot280-elephant-robotics

Prerequisites

All my code for this project is located here on GitHub.

How MoveIt 2 Works with ROS 2 Control

Before we dive into the tutorial, let me explain how MoveIt 2 works with ROS 2 Control by walking through a common real-world use case.

Suppose you have a mobile manipulator, which consists of a wheeled robot base with a robotic arm attached to it.

You want to develop an application that performs a pick and place task. 

Your cool app starts by telling MoveIt 2, “Pick up the object at location A and place it at location B.”

MoveIt 2, with help from Nav 2 (the navigation software stack for ROS 2), plans out the detailed movements needed – reaching for the object, grasping it, lifting it, moving to the new location, and placing it down.

These plans are sent to ROS 2 Control’s Controller Management system, which has specific controllers for the arm, gripper, and base.

The arm controller (e.g. JointTrajectoryController), for example, breaks down the plan into specific joint movements and sends these to the Resource Management system.

The Resource Management system communicates these commands through hardware interfaces to the actual robot parts (or their simulated versions).

As the robot executes the pick and place task, sensors in its joints and gripper send back information about position, force, and status.

This feedback flows back up through the system, allowing your app and MoveIt 2 to monitor progress and make adjustments if needed.

This setup allows you to focus on defining high-level tasks while MoveIt 2 and ROS 2 Control handle the complex details of robot control and movement coordination.

Now let’s look at another diagram which shows the specific controller and topic names. This gives us a more detailed view of how MoveIt 2, ROS 2 Control, and the robot components interact:

ros2_control_mobile_manipulator_control_arch_independent_hardware

Your cool application initiates the process, defining tasks like pick and place operations.

MoveIt 2 contains a path planning component that generates trajectory commands. These commands are sent to the Joint Trajectory Controller, which manages the arm’s movements.

For mobile robots, Nav 2 can send twist commands to the Diff Drive Controller, controlling the base’s motion.

The system includes several specialized controllers:

  • Joint Trajectory Controller for arm movements
  • Forward Velocity Controller for speed control (optional…only needed if you need direct velocity control for high-speed operations)
  • Gripper Controller for end-effector actions (e.g. open and close gripper)
  • Diff Drive Controller for mobile base navigation

These controllers communicate with Hardware Interfaces for the arm, gripper, mobile base, and the Gazebo simulation.

As the robot operates, sensor data flows back through these Hardware Interfaces. This information includes position, velocity, force, and status updates.

The Joint State Broadcaster and Force Torque State Broadcaster collect this feedback data.

This state information (e.g. joint angles) is then forwarded to RViz for visualization and to MoveIt 2 for real-time monitoring and adjustment.

Create a Package

Now that you understand how all the pieces work together on a high level, let’s start setting up our robot with MoveIt 2.

Create a new package called mycobot_moveit_config_manual_setup:

cd ~/ros2_ws/src/mycobot_ros2/
ros2 pkg create --build-type ament_cmake --license BSD-3-Clause mycobot_moveit_config_manual_setup
cd mycobot_moveit_config_manual_setup

Fill in the package.xml file with your relevant information.

gedit package.xml
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>mycobot_moveit_config_manual_setup</name>
  <version>0.0.0</version>
  <description>Contains the files that enable the robot to integrate with Move It 2.</description>
  <maintainer email="automaticaddison@todo.com">Automatic Addison</maintainer>
  <license>BSD-3-Clause</license>

  <buildtool_depend>ament_cmake</buildtool_depend>
  
  <depend>moveit_ros_planning_interface</depend>
  <depend>moveit_ros_move_group</depend>
  <depend>moveit_kinematics</depend>
  <depend>moveit_planners_ompl</depend>
  <depend>moveit_ros_visualization</depend>
  <depend>rviz2</depend>
  <depend>rviz_visual_tools</depend> 

  <exec_depend>moveit_simple_controller_manager</exec_depend>
  <exec_depend>moveit_configs_utils</exec_depend>
  <exec_depend>pilz_industrial_motion_planner</exec_depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

Save the file, and close it.

In a real robotics project, the naming convention for this package would be:

<robot_name>_moveit_config

Create the Configuration Files

Let’s create configuration files that will enable us to tailor our robot for MoveIt 2. We’ll do this process manually first (recommended), and then we will work through how to do this using the MoveIt Setup Assistant

You can see some official examples of configuration files for other robots on the MoveIt resources ROS 2 GitHub.

Create the Config Folder

MoveIt 2 requires configuration files to go into the config folder of the package you created.

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/
mkdir config && cd config

Add SRDF

The first thing we need to do is set up the SRDF File. 

Semantic Robot Description Format (SRDF) is a file that tells MoveIt how your robot prefers to move and interact with its environment. It is a supplement to the URDF file.

The SRDF adds semantic (meaning-based) information to the robot’s description that isn’t included in the URDF (Unified Robot Description Format). This file includes things like:

  • Naming groups of joints or links (e.g., “arm”, “gripper”)
  • Defining default robot poses (e.g., “home”, “closed”, etc.)
  • Which parts of the robot should be checked for colliding with each other during movement.
    • We need to do this step because checking every possible collision between all parts of the robot for each planned movement can be time-consuming, especially for complex robots.
cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/
gedit mycobot_280.srdf

Add this code.

Save the file, and close it.

Let’s go through each section briefly:

  1. <group name=”arm”>: This section defines a group named “arm” that includes a list of joints. The joints listed in this group represent the robot arm.
  2. <group name=”gripper”>: This section defines a group named “gripper” that includes a list of joints related to the robot’s gripper or end-effector.
  3. <group_state name=”home” group=”arm”>: This section defines a named state called “home” for the “arm” group. It specifies the joint values for the arm joints when the robot is in its home position.
  4. <group_state name=”open” group=”gripper”>: This section defines a named state called “open” for the “gripper” group, specifying the joint value for the gripper when it is in its open position.
  5. <disable_collisions>: This section is used to disable collision checking between specific pairs of links. Each <disable_collisions> entry specifies two links and the reason for disabling collision checking between them. The reasons can be “Adjacent” (for adjacent links in the robotic arm), “Never” (for links that will never collide), or “Default” (for links that are not expected to collide in most configurations).

Add Initial Positions

Now let’s create a configuration file for the initial positions.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/
gedit initial_positions.yaml

Add this code.

# Default initial position for each movable joint
initial_positions:
  link1_to_link2: 0.0
  link2_to_link3: 0.0
  link3_to_link4: 0.0
  link4_to_link5: 0.0
  link5_to_link6: 0.0
  link6_to_link6flange: 0.0
  gripper_controller: 0.0

Save the file. This code sets the default initial positions for each movable joint. 

The initial_positions.yaml file in MoveIt specifies the starting joint positions for motion planning, overriding any default positions set in the URDF. It allows you to set a specific initial configuration for your robot in MoveIt without modifying the URDF, providing flexibility in defining the starting point for motion planning tasks.

Add Joint Limits

gedit joint_limits.yaml

Add this code.

default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0

joint_limits:
  link1_to_link2:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  link2_to_link3:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  link3_to_link4:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  link4_to_link5:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  link5_to_link6:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  link6_to_link6flange:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 6.0
  gripper_controller:
    has_velocity_limits: true
    max_velocity: 2.792527
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_deceleration_limits: true
    max_deceleration: -5.0
    has_jerk_limits: false
    max_jerk: 300.0

Save the file.

This code sets the velocity and acceleration limits for each joint in our robotic arm, which is used by MoveIt 2 to control the robot’s movements.

Even though we have joint limits for velocity already defined in the URDF, this YAML file allows for overriding. Defining joint limits specific to MoveIt 2 is useful if you want to impose stricter or different limits for particular applications without modifying the URDF. It provides flexibility in adjusting the robot’s behavior for different tasks.

Add Kinematics

gedit kinematics.yaml

Add this code, and save the file. 

# Configures how a robot calculates possible positions and movements of its joints 
# to reach a desired point. It specifies which mathematical methods (solvers) to use, 
# how long to try, and how precise these calculations should be.
arm: # Name of the joint group from the SRDF file
  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin # Plugin used for solving kinematics
  kinematics_solver_search_resolution: 0.005 #  Granularity (in radians for revolute joints) used by the solver when searching for a solution.
  kinematics_solver_timeout: 0.05 # Maximum time the solver will spend trying to find a solution for each planning attempt
  position_only_ik: false # If true, the solver will only consider the position of the end effector, not its orientation
  kinematics_solver_attempts: 5 # How many times the solver will try to find a solution

# Typically we don't need a complex kinematics solver for the gripper. This is for demonstration purposes only.  
gripper:
  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
  kinematics_solver_search_resolution: 0.005
  kinematics_solver_timeout: 0.05
  position_only_ik: false
  kinematics_solver_attempts: 3
  
arm_with_gripper:
  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
  kinematics_solver_search_resolution: 0.005
  kinematics_solver_timeout: 0.05
  position_only_ik: false
  kinematics_solver_attempts: 5

This file configures how MoveIt 2 calculates possible positions and movements of the robot’s arm to reach a desired point in space. It specifies the mathematical methods, precision, and time limits for these calculations, which MoveIt 2 uses to plan the robot’s movements.

Add Controllers

gedit moveit_controllers.yaml

Add this code, and save the file. 

# This file configures the controller management for MoveIt, specifying which controllers are available,
# the joints each controller handles, and the type of interface (e.g. FollowJointTrajectory).
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager  # Specifies the controller manager to use.

# Define the controllers configured using the ROS 2 Control framework.
moveit_simple_controller_manager:
  controller_names:
    - arm_controller   # Name of the controller for the robotic arm.
    - grip_controller  # Name of the controller for the gripper.
    - grip_action_controller # Other controller for the gripper (recommended)

  # Configuration for the arm_controller.
  arm_controller:
    action_ns: follow_joint_trajectory   # ROS action namespace to which MoveIt sends trajectory commands.
    type: FollowJointTrajectory          # Type of the controller interface; follows a joint trajectory.
    default: true                        # This controller is the default for the joints listed below.
    joints:                              # List of joints that the arm_controller manages.
      - link1_to_link2
      - link2_to_link3
      - link3_to_link4
      - link4_to_link5
      - link5_to_link6
      - link6_to_link6flange

  # Configuration for the grip_controller.
  grip_controller:
    action_ns: follow_joint_trajectory  
    type: FollowJointTrajectory         
    default: false                    
    joints:                           
      - gripper_controller      
  
  # Configuration for the grip_action_controller.    
  grip_action_controller:  
    action_ns: gripper_cmd 
    type: GripperCommand
    default: true
    joints:
      - gripper_controller       


This yaml file tells MoveIt 2 how to convert its motion plans into instructions that the ROS 2 controllers can understand and execute on the real (or simulated) robot. Without this, MoveIt 2 wouldn’t know how to make the robot actually move using the ROS 2 control system.

MoveIt 2 sends desired joint positions or trajectories to ROS 2 controllers, which then manage the low-level control of the robot’s motors. This integration allows MoveIt 2 to focus on high-level motion planning while relying on ROS 2 control for the actual execution on the robot hardware.

We see that three ROS 2 controllers are available:

  • arm_controller: This is a Joint Trajectory Controller for the robot arm
  • grip_controller: This is a Joint Trajectory Controller for the gripper (optional)
  • grip_action_controller: This is a Gripper Action Controller for the gripper

We also see a list of joints associated with each controller.

The arm controller uses the “FollowJointTrajectory” action interface. The FollowJointTrajectory action interface is a standardized interface in ROS (Robot Operating System) for controlling the joint positions of a robot over time. It allows MoveIt 2 to send a trajectory, which is a sequence of joint positions and their corresponding timestamps, to the robot’s joint controllers.

How it works:

  1. MoveIt 2 plans a movement, which results in a series of joint positions over time.
  2. This plan is packaged into a “trajectory” – think of it as a list of goal positions (in radians) for each joint.
  3. MoveIt 2 sends this trajectory to the appropriate ROS 2 controller using the FollowJointTrajectory action interface. This interface is like a protocol MoveIt 2 uses to communicate with the controllers.
  4. The ROS 2 controller receives this trajectory, processes it, and relays it to the hardware interface.
  5. The hardware interface sends the commands to the microcontroller (e.g. Arduino) to move the robot’s joints accordingly.

Add Cartesian Speed and Acceleration Limits

For motion planning for our robotic arm, we are going to use the Pilz industrial motion planner.

Pilz focuses on simple, predictable movements like straight lines, circles, and direct point-to-point paths. It works by calculating a clear, predefined route for each part of the robot to follow, ensuring smooth and safe motion from start to finish.

Think of Pilz as a careful driver that always takes known, reliable routes rather than trying to find creative shortcuts, making it perfect for precise tasks where you want consistent, controlled movements.

While default planners like OMPL (Open Motion Planning Library) work best for dynamic environments where you can have unexpected obstacles (people moving around, objects left on tabletops and counters, etc.), the structured and predictable nature of Pilz is advantageous in a scenario where the environment is well-structured and controlled.

Open a new file where we will define the Cartesian limits:

gedit pilz_cartesian_limits.yaml  
# Defines the Cartesian movement limits for a robotic arm using the Pilz Planner.
# The values are typically determined based on a combination of the robot manufacturer's 
# specifications, practical testing, and considerations for the specific tasks the robot will perform.
cartesian_limits:
  max_trans_vel: 1.0  # Maximum translational velocity in meters per second. Specifies how fast the end effector can move in space.
  max_trans_acc: 2.25 # Maximum translational acceleration in meters per second squared. Determines how quickly the end effector can increase its speed.
  max_trans_dec: -5.0 # Maximum translational deceleration in meters per second squared. Specifies how quickly the end effector can decrease its speed.
  max_rot_vel: 1.57   # Maximum rotational velocity in radians per second. Controls the speed at which the end effector can rotate.

Save the file, and close it.

This file sets speed and acceleration limits for a robotic arm’s movement in space. It defines how fast and quickly the robot’s end effector can move and rotate in Cartesian space (X, Y, Z direction) to ensure safe and efficient operation within the robot’s workspace.

Why do we need this file if we have already set velocity limits inside the URDF?

The URDF and the MoveIt configuration files serve different purposes when it comes to controlling the robot’s motion. The URDF contains velocity limits for each individual joint, which determine how fast each joint can move. These limits are important for controlling the speed of the individual joints. For example:

<joint name="joint_name" type="revolute">
  <limit lower="-2.879793" upper="2.879793" effort="5.0" velocity="2.792527"/>
</joint>

On the other hand, the cartesian_limits in the MoveIt configuration are used to control the speed and motion of the robot’s gripper in 3D space. These limits define how fast the gripper can move and rotate in the world coordinate frame (X, Y, Z axes). The cartesian_limits are essential for planning the overall motion of the robot and ensuring that it moves safely and efficiently when performing tasks.

So, while the URDF velocity limits are important for controlling individual joints, the MoveIt cartesian_limits are still necessary for proper motion planning and control of the gripper’s movement in 3D space.

By the way, in the context of the file name “pilz_cartesian_limits.yaml”, “pilz” refers to Pilz GmbH & Co. KG, a German automation technology company that specializes in safe automation solutions, including robotics.

Add a Planning Pipeline File for the Pilz Industrial Motion Planner

To make all this work, we need to add a file called pilz_industrial_motion_planner_planning_planner.yaml.

Here is an example file from MoveIt’s GitHub

This file preprocesses the robot’s motion planning request to make sure it meets certain safety and feasibility criteria, like ensuring the robot’s starting position is safe and within allowed limits before planning its movement.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/config/
gedit pilz_industrial_motion_planner_planning.yaml

Add this code.

planning_plugin: pilz_industrial_motion_planner/CommandPlanner
request_adapters: >-
  default_planner_request_adapters/FixWorkspaceBounds
  default_planner_request_adapters/FixStartStateBounds
  default_planner_request_adapters/FixStartStateCollision
  default_planner_request_adapters/FixStartStatePathConstraints
default_planner_config: PTP
capabilities: >-
    pilz_industrial_motion_planner/MoveGroupSequenceAction
    pilz_industrial_motion_planner/MoveGroupSequenceService

Save the file, and close it.

Add an RViz Configuration File

Let’s create a file that sets the parameters for visualizing all this in RViz.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup
mkdir rviz && cd rviz
gedit move_group.rviz

Add this code.

Save the file, and close it.

Create a Launch File

Let’s create a launch file.

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup

Create a new launch folder.

mkdir launch && cd launch
gedit move_group.launch.py

Add this code.

# Author: Addison Sears-Collins
# Date: July 31, 2024
# Description: Launch MoveIt 2 for the myCobot robotic arm

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, EmitEvent, RegisterEventHandler
from launch.conditions import IfCondition
from launch.event_handlers import OnProcessExit
from launch.events import Shutdown
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from moveit_configs_utils import MoveItConfigsBuilder
import xacro


def generate_launch_description():

    # Constants for paths to different files and folders
    package_name_gazebo = 'mycobot_gazebo'
    package_name_moveit_config = 'mycobot_moveit_config_manual_setup'

    # Set the path to different files and folders
    pkg_share_gazebo = FindPackageShare(package=package_name_gazebo).find(package_name_gazebo)
    pkg_share_moveit_config = FindPackageShare(package=package_name_moveit_config).find(package_name_moveit_config)

    # Paths for various configuration files
    urdf_file_path = 'urdf/ros2_control/gazebo/mycobot_280.urdf.xacro'
    srdf_file_path = 'config/mycobot_280.srdf'
    moveit_controllers_file_path = 'config/moveit_controllers.yaml'
    joint_limits_file_path = 'config/joint_limits.yaml'
    kinematics_file_path = 'config/kinematics.yaml'
    pilz_cartesian_limits_file_path = 'config/pilz_cartesian_limits.yaml'
    initial_positions_file_path = 'config/initial_positions.yaml'
    rviz_config_file_path = 'rviz/move_group.rviz'

    # Set the full paths
    urdf_model_path = os.path.join(pkg_share_gazebo, urdf_file_path)
    srdf_model_path = os.path.join(pkg_share_moveit_config, srdf_file_path)
    moveit_controllers_file_path = os.path.join(pkg_share_moveit_config, moveit_controllers_file_path)
    joint_limits_file_path = os.path.join(pkg_share_moveit_config, joint_limits_file_path)
    kinematics_file_path = os.path.join(pkg_share_moveit_config, kinematics_file_path)
    pilz_cartesian_limits_file_path = os.path.join(pkg_share_moveit_config, pilz_cartesian_limits_file_path)
    initial_positions_file_path = os.path.join(pkg_share_moveit_config, initial_positions_file_path)
    rviz_config_file = os.path.join(pkg_share_moveit_config, rviz_config_file_path)

    # Launch configuration variables
    use_sim_time = LaunchConfiguration('use_sim_time')
    use_rviz = LaunchConfiguration('use_rviz')

    # Declare the launch arguments
    declare_use_sim_time_cmd = DeclareLaunchArgument(
        name='use_sim_time',
        default_value='true',
        description='Use simulation (Gazebo) clock if true')

    declare_use_rviz_cmd = DeclareLaunchArgument(
        name='use_rviz',
        default_value='true',
        description='Whether to start RViz')

    # Load the robot configuration
    # Typically, you would also have this line in here: .robot_description(file_path=urdf_model_path)
    # Another launch file is launching the robot description.
    moveit_config = (
        MoveItConfigsBuilder("mycobot_280", package_name=package_name_moveit_config)
        .trajectory_execution(file_path=moveit_controllers_file_path)
        .robot_description_semantic(file_path=srdf_model_path)
        .joint_limits(file_path=joint_limits_file_path)
        .robot_description_kinematics(file_path=kinematics_file_path)
        .planning_pipelines(
            pipelines=["ompl", "pilz_industrial_motion_planner", "stomp"],
            default_planning_pipeline="pilz_industrial_motion_planner"
        )
        .planning_scene_monitor(
            publish_robot_description=False,
            publish_robot_description_semantic=True,
            publish_planning_scene=True,
        )
        .pilz_cartesian_limits(file_path=pilz_cartesian_limits_file_path)
        .to_moveit_configs()
    )
    
    # Start the actual move_group node/action server
    start_move_group_node_cmd = Node(
        package="moveit_ros_move_group",
        executable="move_group",
        output="screen",
        parameters=[
            moveit_config.to_dict(),
            {'use_sim_time': use_sim_time},
            {'start_state': {'content': initial_positions_file_path}},
        ],
    )

    # RViz
    start_rviz_node_cmd = Node(
        condition=IfCondition(use_rviz),
        package="rviz2",
        executable="rviz2",
        arguments=["-d", rviz_config_file],
        output="screen",
        parameters=[
            moveit_config.robot_description,
            moveit_config.robot_description_semantic,
            moveit_config.planning_pipelines,
            moveit_config.robot_description_kinematics,
            moveit_config.joint_limits,
            {'use_sim_time': use_sim_time}
        ],
    )
    
    exit_event_handler = RegisterEventHandler(
        condition=IfCondition(use_rviz),
        event_handler=OnProcessExit(
            target_action=start_rviz_node_cmd,
            on_exit=EmitEvent(event=Shutdown(reason='rviz exited')),
        ),
    )
    
    # Create the launch description and populate
    ld = LaunchDescription()

    # Declare the launch options
    ld.add_action(declare_use_sim_time_cmd)
    ld.add_action(declare_use_rviz_cmd)

    # Add any actions
    ld.add_action(start_move_group_node_cmd)
    ld.add_action(start_rviz_node_cmd)
    
    # Clean shutdown of RViz
    ld.add_action(exit_event_handler)

    return ld

Save the file, and close it.

This launch file launches MoveIt and RViz.

Looking at the source code for the moveit_configs_builder helped me to complete this launch file.

Create a Setup Assistant File

The .setup_assistant file is typically created automatically when you use the MoveIt Setup Assistant to configure your robot.

Create a new file named .setup_assistant in the root directory of your MoveIt configuration package (e.g., mycobot_moveit_config_manual_setup).

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/
gedit .setup_assistant

Add this code:

moveit_setup_assistant_config:
  URDF:
    package: mycobot_gazebo
    relative_path: urdf/ros2_control/gazebo/mycobot_280.urdf.xacro
    xacro_args: ""
  SRDF:
    relative_path: config/mycobot_280.srdf
  CONFIG:
    author_name: AutomaticAddison
    author_email: addison@todo.com
    generated_timestamp: 1690848000

Save the file, and close it.

Set file permissions.

sudo chmod 644 .setup_assistant

Edit package.xml

Let’s edit the package.xml file with the dependencies.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup
gedit package.xml

Add this code.

Save the file, and close it.

Edit CMakeLists.txt

Update CMakeLists.txt with the new folders we have created.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup
gedit CMakeLists.txt

Add this code.

cmake_minimum_required(VERSION 3.8)
project(mycobot_moveit_config_manual_setup)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
find_package(moveit_ros_move_group REQUIRED)
find_package(moveit_kinematics REQUIRED)
find_package(moveit_planners_ompl REQUIRED)
find_package(moveit_ros_visualization REQUIRED)
find_package(rviz2 REQUIRED)
find_package(rviz_visual_tools REQUIRED) 

# Copy necessary files to designated locations in the project
install (
  DIRECTORY config launch rviz scripts
  DESTINATION share/${PROJECT_NAME}
)

# Install the .setup_assistant file
install(
  FILES .setup_assistant
  DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

Save the file, and close it.

Build the Package

Now let’s build the package.

cd ~/ros2_ws/
colcon build
source ~/.bashrc

Launch the Demo and Configure the Plugin

Begin by launching the robot in Gazebo along with all the controllers (i.e. arm_controller, grip_controller). Since we are going to launch RViz using the MoveIt launch file, we can set the use_rviz flag to False. 

ros2 launch mycobot_gazebo mycobot_280_arduino_bringup_ros2_control_gazebo.launch.py use_rviz:=false

This will:

  • Start Gazebo
  • Spawn the robot
  • Start the robot_state_publisher
  • Load and start the necessary controllers (joint_state_broadcaster, arm_controller, grip_controller)

If you look in the logs, you will see the joint_state_broadcaster, arm_controller, and grip_controller are loaded and activated.

Launch MoveIt and RViz.

ros2 launch mycobot_moveit_config_manual_setup move_group.launch.py 

This will:

  • Start the move_group node
  • Launch RViz with MoveIt configuration
  • Use the simulation time from Gazebo

Rather than launching two launch files one after the other, you can put them both into a bash script like this (call the file some name like “robot.sh”):

#!/bin/bash
# Single script to launch the mycobot with Gazebo, RViz, and MoveIt 2

cleanup() {
    echo "Restarting ROS 2 daemon to cleanup before shutting down all processes..."
    ros2 daemon stop
    sleep 1
    ros2 daemon start
    echo "Terminating all ROS 2-related processes..."
    kill 0
    exit
}

trap 'cleanup' SIGINT;
ros2 launch mycobot_gazebo mycobot_280_arduino_bringup_ros2_control_gazebo.launch.py use_rviz:=false &
sleep 10
ros2 launch mycobot_moveit_config_manual_setup move_group.launch.py

Be sure to set permissions to this bash script before running it.

sudo chmod +x robot.sh

Then run this command to launch everything at once.

bash robot.sh

Here is what your screen should look like when everything is loaded properly. You will notice that on the right-hand side of Gazebo I closed the two panels. You can close them by right-clicking and hitting “Close”.

2-loading-gz-sim-gazebo-moveit2

Let’s check out the active topics:

ros2 topic list
3-ros2-topic-list

The active nodes are:

ros2 node list
4-ros2-node-list

Here are our available action servers:

ros2 action list
5-ros2-action-list

Here are our services. You will see we have a lot of services. This page at the ROS 2 tutorials shows you how we can call services from the command line.

ros2 service list

Let’s check out the parameters for the different nodes my launching a GUI tool called rqt_reconfigure:

sudo apt install ros-$ROS_DISTRO-rqt-reconfigure
rqt --standalone rqt_reconfigure
9-parameters-rqt-reconfigure

Click “Refresh”.

Click on any of the nodes to see the parameters for that node. For example, let’s take a look at the moveit_simple_controller_manager node.

This tool enables you to see if the parameters you set in the config file of your MoveIt package were set correctly. 

Explore MoveIt in RViz

We will now roughly follow this official MoveIt Quickstart in RViz tutorial which walks you through the main features provided by the MoveIt RViz plugins.

First, click on the Displays panel in the upper left.

Under Global Options, make sure the Fixed Frame is set to “base_link”

Scroll down to the MotionPlanning plugin.

Make sure the Robot Description field is set to robot_description.

11-set-to-robot-description

Make sure the Planning Scene Topic field is set to /monitored_planning_scene. 

Make sure the Trajectory Topic under Planned Path is set to /display_planned_path.

12-display-planned-path

In the Planning Request section,  make sure the Planning Group is set to arm. You can also see this in the MotionPlanning panel in the bottom left.

13-planning-group-arm

Play With the Robotic Arm

Rviz has four different visualizations for MoveIt. These visualizations are overlapping.

  1. The robot’s configuration in the /monitored_planning_scene planning environment:
    • Planning Scene -> Scene Robot -> Show Robot Visual checkbox
  2. The planned path for the robot:
    • Motion Planning -> Planned Path -> Show Robot Visual checkbox
  3. Green: The start state for motion planning:
    • MotionPlanning -> Planning Request -> Query Start State checkbox
  4. Orange: The goal state for motion planning:
    • MotionPlanning -> Planning Request -> Query Goal State checkbox

You can toggle each of these visualizations on and off using the checkboxes in the Displays panel.

Interact With the Robotic Arm

Now let’s configure our RViz so that all we have are the scene robot, the starting state, and the goal state.

  1. Check the Motion Planning -> Planned Path -> Show Robot Visual checkbox
  2. Uncheck the Planning Scene -> Scene Robot -> Show Robot Visual checkbox
  3. Uncheck the MotionPlanning -> Planning Request -> Query Start State checkbox
  4. Check the MotionPlanning -> Planning Request -> Query Goal State checkbox

The orange colored robot represents the desired Goal State

14-orange-colored-goal-state

Find the “Joints” tab in the bottom MotionPlanning panel. This lets you control individual joints of the robot.

Try moving the sliders for the joints, and watch how the robot arm changes its pose. 

Uncheck the MotionPlanning -> Planning Request -> Query Goal State checkbox.

Check the MotionPlanning -> Planning Request -> Query Start State checkbox.

The green colored robot is used to set the Start State for motion planning.

15-start-state

Use Motion Planning

Now it’s time to plan a movement for your robotic arm using RViz and MoveIt 2.

In the Displays panel in RViz, do the following…

Uncheck the MotionPlanning -> Planning Request -> Query Goal State checkbox

Check the MotionPlanning -> Planning Request -> Query Start State checkbox.

You can see if any links are in collision by going to the MotionPlanning window at the bottom and moving to the “Status” tab.

Move the green (Start State) to where you want the movement to begin.

Rather than using the interactive marker, I find it easier to go to the “Joints” tab in the Motion Planning window at the bottom. This lets you control individual joints of the robot to get your desired Start State.

16-joints-panel

Uncheck the MotionPlanning -> Planning Request -> Query Start State checkbox.

Check the MotionPlanning -> Planning Request -> Query Goal State checkbox.

Move the orange (Goal State) to where you want the movement to end.

Check the MotionPlanning -> Planning Request -> Query Start State checkbox.

If you have a strong computer, you can check the MotionPlanning -> Planned Path -> Show Trail checkbox. This will show you a trail of the planned path. This step is optional.

17-show-trail

Now let’s plan a motion. Look for the “MotionPlanning” window at the bottom-left part of the screen.

Click the Context tab.

16b-ptp
  • Select CIRC (circular motion) if you want the end-effector to move in a circular arc.
  • Select LIN (linear motion) if you want the end effector to move in a straight line between the start and goal positions
  • Select PTP (point-to-point motion) if you want the quickest joint movement between start and goal configurations.
pilz
Image Source: Picknik Robotics

I will click PTP.

Now click the Planning tab.

18-motion-planning-velocity-acceleration-scaling

Click the Plan button to generate a motion plan between the start and goal state.

The system will calculate a path, and you should see a preview of the planned motion in the 3D visualization window.

Review the planned path carefully to ensure it’s appropriate and collision-free.

If you’re not satisfied with the plan, you can adjust the start and goal states in the 3D view and plan again.

Once you’re happy with the plan, click the Plan & Execute button to make the robot carry out the planned motion.

You should see your simulated robotic arm moving in both Gazebo and RViz.

If you want to speed things up, you can tweak the Velocity Scaling figures on the Planning tab. You can make them all 1.0 for example.

Then click Plan & Execute again.

Keep setting new Goal States and moving your arm to different poses. 

Be careful not to move your robot into a Goal State where the robot appears red. Red links on your robot mean the robot is colliding with itself.

19-red-colliding-links

If you want to open and close the gripper. The steps are the same.

Go to the MotionPlanning window at the bottom-left.

Go to the Planning tab.

Change the Planning Group to gripper.

Go to the Context tab.

Select PTP under the pilz_industrial_motion_planner.

Click the Planning tab again.

Select closed as the Goal State. Remember this is one of the states we configured in the SRDF file.

Click Plan & Execute. No need to click Plan first and then Execute since this is a simple motion.

You should see the gripper close in Gazebo.

20-gripper-closed

You can also make motion plans for the combined arm and gripper group. Have fun with it, and play around to get a feel for MoveIt2 in Rviz. 

Don’t forget that every time you change a planning group, you need to go to the Context tab and select PTP.

You can try other planners other than Pilz if you like. 

I have set up OMPL and STOMP as some alternative motion planning libraries. Just use the dropdown menu on the Context tab.

The two parameters files that are required to use OMPL (ompl_planning.yaml) and STOMP (stomp_planning.yaml) are in the mycobot_moveit_config_manual_setup/config folder.

A good planner to use if you are in doubt of what to use is the ompl/RRTConnectkConfigDefault planner. It works well for a wide variety of use cases.

Introspecting Trajectory Waypoints

Understanding how your robot moves in detail is important for ensuring smooth and safe operations. Let’s explore a tool that allows us to do just that:

Add a new tool to RViz.

  • Click on the “Panels” menu
  • Choose “Trajectory – Trajectory Slider”
  • You’ll see a new slider appear in RViz
21-panels-trajectory-slider

Plan a movement:

  • Set a new goal pose for the robotic arm.
  • Click the “Plan” button

Use the new Trajectory Slider:

  • Move the slider to see each step of the robot’s planned movement
  • Press the “Play” button to watch the whole movement smoothly
22-trajectory-slider

Remember: If you change where you want the robot to go, always click “Plan” again before using the slider or “Play” button. This makes sure you’re looking at the newest plan, not an old one.

This tool helps you understand exactly how your robot will move from start to finish.

Plan Cartesian Motions

Sometimes, you want your robot to move in a straight line. Here’s how to do that.

Go to the MotionPlanning panel at the bottom-right of the screen.

Click the Planning tab.

Click the Use Cartesian Path checkbox.

What does this do?

  • When checked, the robot will try to move its end-effector in a straight line.
  • This is useful for tasks that need precise, direct movements, like drawing a straight line or moving directly towards an object.

Why is this important?

  • Normal planning might move the robot’s arm in a curved or complex path.
  • Cartesian planning ensures a more predictable, straight-line movement.

Try planning some movements with this option on and off to see the difference in how the robot moves.

That’s it! Keep building!