Getting Started with the MoveIt 2 Task Constructor

moveit-task-constructor-core-concepts

In this tutorial, I will guide you through the core concepts of the MoveIt Task Constructor for ROS 2. You will also install it on your computer.

The MoveIt 2 Task Constructor (MTC) is designed to make complex robot tasks easier to program and manage. 

At its core, the Task Constructor breaks big tasks into smaller, more manageable pieces called stages. These stages can be mixed and matched like building blocks. They can also share information with each other, making it easier to create smooth, coordinated robot actions.

Overall, the goal of the MTC is to give robot programmers a set of tools that make their job more efficient and help them create more reliable and adaptable robot behaviors.

Prerequisites

We will just focus on concepts in this tutorial. In future tutorials, you will learn how to build your own applications using the MTC. You can check out my sample code here on GitHub. Don’t worry. I will go through all that in a later tutorial.

MTC Core Concepts

The MoveIt Task Constructor (MTC) is built around three core concepts that work together in harmony to create a comprehensive system for robot task planning.

Task

A Task is like a big plan for a robot. It is made up of a series of smaller steps that the robot needs to do to complete a job. 

Think of a task as a recipe for the robot to follow. Each Task is built from a sequence of Stages, which are the individual steps or actions the robot needs to take.

Stage

A Stage is a single step within a Task. It is a specific action or calculation the robot needs to perform. 

For example, a Stage might be “move the arm to a certain position” or “open the gripper.” 

Stages can be simple or complex, and they work together to form the complete Task. 

Each Stage produces what’s called a SubSolution, which is the result of that particular step.

Planning Scene

In the previous tutorial, you had experience adding a collision object to the planning scene.

The Planning Scene is the virtual model of the robot’s world. It includes information about the robot itself, any objects in its environment, and any constraints or rules the robot needs to follow. 

When the robot is planning its movements or actions, MoveIt uses this Planning Scene to figure out what the robot can and cannot do. 

The Planning Scene gets updated as the robot moves through its Task, keeping track of changes in the environment.

Stage Types

Let’s take a closer look at stages in the MTC

The MTC uses different types of Stages to handle various aspects of task planning. These Stage types are designed to work together, providing a versatile toolkit for creating complex robot behaviors. The three main types of Stages in the MTC are Generator Stage, Propagator Stage, and Connector Stage. 

1-stage-types

Source: PickNik Inc.

Generator Stage

An MTC task starts with a Generator stage. This stage receives no input from adjacent stages. It doesn’t care what happens before it or after it.

The results that are computed in this stage are passed forward and backward.

Let’s look at some examples of Generator Stage types.

Examples

CurrentState is the most important generator stage. This is like taking a snapshot of where the robot is right now. It captures the robot’s current position, the state of its joints, and any objects it might be holding or interacting with. 

CurrentState generates the starting point for planning what the robot will do next.

GeneratePose is another type of generator stage. GeneratePose is about coming up with possible positions for the robot’s arm or gripper. 

For example, if the robot needs to pick up an object, GeneratePose might generate different ways the gripper could be positioned to grab the object. It’s like brainstorming potential positions for the robot.

Propagator Stage

A propagator stage is like a one way street. It receives an input from an adjacent stage, processes that input, and then generates an output for the next stage.

Examples

MoveTo is a propagating stage type because it takes the robot arm’s current state as input and produces a new state as output. 

For example, the MoveTo stage might start with the arm at rest and end with the arm reaching into a parts bin. 

MoveRelative is another propagating stage type because it advances the robot’s state incrementally. It takes the current arm position as input and outputs a new position based on a relative movement. 

For example, during the MoveRelative stage, the arm might move 10cm upward relative to where it currently is in the world, propagating the state forward by this small, relative change.

ModifyPlanningScene takes the current planning scene (the virtual model of the robot’s environment) as input, along with pre-programmed instructions for how to modify that scene (e.g. add or remove objects from the virtual environment). It then outputs an updated planning scene.

Connector Stage (i.e. Connectors)

Unlike Propagators, Connectors do not send results to other stages. Instead, they are like bridges that plan movements between two different arbitrary stages.

An example of a Connector Stage is finding a way to move the arm from its current position to a specific point.

Bringing It All Together

The three stage classes we mentioned above are called “primitive” stage classes. They are the basic building blocks for tasks in MoveIt 2.

Below is an example of how the stages might be structured for a sample pick and place task. The arrow and bar symbols represent the different stage types.

2-example-stages

Source: PickNik Inc.

Generator Stage (↕️):

  • This stage creates new possibilities.
  • It is like coming up with ideas for the robot to try.
  • Examples: Figuring out different poses the robot could use, or setting a specific position for the robot.

Propagator Stage (↓ or ↑ or both):

  • This stage takes an input and figures out what to do next.
  • It can work forward (↓), backward (↑), or both ways.
  • Examples: Planning how to move in a straight line, or checking if a movement is safe.

Connector Stage (||):

  • This stage links two different states or positions.
  • It’s like finding a path between where the robot is and where it needs to go.
  • Example: Planning how to move freely from a starting position to an end position.

So there you have it. Stages either generate, propagate, or connect.

Containers (grouping primitive stages to perform a task)

MoveIt Task Constructor (MTC) has a concept called Containers. A Container is like a box that can hold one or more stages or even other containers. It helps group related stages together and create a hierarchy or structure for complex tasks. 

There are three types of container stages: wrapper, serial, and parallel. Let’s go through each one.

3-containers

Source: PickNik Inc.

Wrapper Container

This container is used to modify or filter the solutions of a stage it contains. The wrapper modifies how a single task is performed without changing the core action.

Example: Wrap a pose generator with an IK (Inverse Kinematics) solver

  • A pose generator is a component that comes up with possible positions and orientations for the robot’s end-effector (like its hand or gripper) to grasp an object.
  • An IK (Inverse Kinematics) solver figures out how the robot’s joints should be positioned to achieve the specific end-effector (gripper) pose calculated in #1.
  • By wrapping the pose generator in step #1 with an IK solver in step #2, you’re creating a system that not only generates potential grasping poses but also immediately checks if the robot can actually achieve those poses, ensuring that only reachable and feasible grasping positions are considered.

Serial Containers

This container contains a sequence of stages that must be followed in order. 

Example:

  1. Approach the object (stage 1 – propagator)
  2. Generate the grasp pose (stage 2 – generator)
  3. Grasp the object (stage 3 – propagator)
  4. Lift the object (stage 4 – propagator)

The robot needs to complete all these steps in sequence to successfully complete the task.

Parallel Containers

This container allows for the simultaneous or alternative execution of multiple stages. It can include:

  • Alternative Stages:
    • Alternative Stages are different options to achieve the same goal, where only one needs to succeed. 
    • For example, you might have stages for picking an object with either the left hand or the right hand. The task will be successful if the robot can pick with either hand.
  • Fallback Stages:
    • Fallback Stages are backup options that are tried in order if earlier ones fail. For instance, you might have a default motion planner, and if that doesn’t work, it will try alternative planners. This ensures that even if the preferred method fails, there are other ways to complete the task.
  • Merger Stages:
    • Merger Stages allow multiple distinct actions to happen at the same time. 
    • For example, the robot could open its gripper while simultaneously moving its arm to a new position. This can make tasks more efficient by combining compatible actions.

Parallel Containers give flexibility in how tasks are performed, allowing for multiple approaches, backup plans, and simultaneous actions. This makes robotic tasks more adaptable and robust.

Example: Pick and Place

Have a look at this diagram and see how containers and stage types could be organized in a sample pick and place application.

4-have-a-look-pick-place

Source: PickNik Inc.

That covers the basic concepts of the MTC.

If you want to do further reading, check out this link at the official MoveIt 2 website.

Install MoveIt Task Constructor

Now that we have covered the concepts, let’s get hands-on experience with the MTC.

Install warehouse_ros_mongo

First, we need to install the warehouse_ros_mongo package.

The warehouse_ros_mongo package is a database tool for ROS 2 that allows you to save, retrieve, and manage important information about your robot’s positions and configurations, acting like a digital memory bank for your robot.

Open a terminal window, and let’s install some dependencies needed by the warehouse_ros_mongo package.

sudo apt-get install gnupg curl

We will now install mongo_db. Follow these official instructions.  We will also walk through it together now (we are doing version 7.0 now below, so the exact version you need to download will likely change in the future).

curl -fsSL https://www.mongodb.org/static/pgp/server-7.0.asc | \
   sudo gpg -o /usr/share/keyrings/mongodb-server-7.0.gpg \
   --dearmor
echo "deb [ arch=amd64,arm64 signed-by=/usr/share/keyrings/mongodb-server-7.0.gpg ] https://repo.mongodb.org/apt/ubuntu jammy/mongodb-org/7.0 multiverse" | sudo tee /etc/apt/sources.list.d/mongodb-org-7.0.list
sudo apt-get update
sudo apt-get install -y mongodb-org

Now start the MongoDB service.

sudo systemctl start mongod

If you receive an error similar to the following when starting mongod:

Failed to start mongod.service: Unit mongod.service not found.

Run the following command first:

sudo systemctl daemon-reload

Then run the start command above again.

Now run this command to enable MongoDB to start when you boot up your machine:

sudo systemctl enable mongod

Verify everything is up and running fine:

sudo systemctl status mongod

If MongoDB is running, it should show the service as active.

5-mongo-db-active

Now let’s install the warehouse_ros_mongo package.

Open a terminal window, and navigate to your ROS 2 workspace’s source folder:

cd ~/ros2_ws/src
git clone https://github.com/moveit/warehouse_ros_mongo.git -b ros2
cd warehouse_ros_mongo/
gedit package.xml

Remove this line:

<depend>mongodb</depend>

Save the file, and close it.

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

Type your password and press Enter to install any missing packages.

colcon build
source ~/.bashrc (OR source ~/ros2_ws/install/setup.bash if you haven’t set up your bashrc file to source your ROS distribution automatically with “source ~/ros2_ws/install/setup.bash”)

Install the MoveIt Task Constructor Package

Open a new terminal window, and type:

cd ~/ros2_ws/src
git clone git@github.com:moveit/moveit_task_constructor.git -b ros2
cd ~/ros2_ws
rosdep update
rosdep install --from-paths src --ignore-src -r -y

Type your password and press Enter to install any missing packages.

cd ~/ros2_ws/
colcon build

You can ignore this error:

— stderr: rviz_marker_tools                                                                                                                                 rviz_marker_tools: You did not request a specific build type: Choosing ‘Release’ for maximum performance

source ~/.bashrc

Fix Build Errors

I had a lot of build errors at this stage. Build errors are common for open-source ROS 2 packages you pull directly off of GitHub, so no need to worry.  

Note that the build errors I discuss below are for ROS 2 Iron. You will have different build errors for other versions of ROS 2.

I will show you how to troubleshoot these errors. Learning how to troubleshoot errors is a good skill to have for ROS 2 since you will often be using packages developed by third parties.

Let’s summarize the errors we have now:

  • Error in cartesian_path.cpp: ‘relative’ is not a member of ‘moveit::core::JumpThreshold’
  • Errors in pipeline_planner.cpp:
    • ‘const class moveit::core::MoveItErrorCode’ has no member named ‘message’
    • Could not convert from ‘<brace-enclosed initializer list>’ to ‘moveit::task_constructor::solvers::PlannerInterface::Result’

To fix these errors, we need to dive into the move_it_task_constructor source code.

Let’s go to the cartesian_path.cpp file.

cd ~/ros2_ws/src/moveit_task_constructor/core/src/solvers/
gedit cartesian_path.cpp

Change this line:

moveit::core::JumpThreshold::relative(props.get<double>(“jump_threshold”)), is_valid,

To this:

moveit::core::JumpThreshold(props.get<double>(“jump_threshold”)), is_valid, 

We can see the JumpThreshold API was updated with a relative member not too long ago, so we need to revert to the older JumpThreshold API.

Now let’s look at pipeline_planner.cpp.

cd ~/ros2_ws/src/moveit_task_constructor/core/src/solvers/
gedit pipeline_planner.cpp

I can see that a change was made on March 9, 2024.

6-get-previous-commit

They added the following line, which is causing our issues:

return { false, solution.error_code.message };

Replace that line with this:

return { false, “Error code: ” + std::to_string(solution.error_code.val) };

Save the file, and close it.

Now build again.

cd ~/ros2_ws/
colcon build

The stderr output for moveit_task_constructor_core is just a warning about using serial compilation for LTRANS jobs, which is not a critical issue.

The other stderr outputs were mostly informing that a Release build type was chosen for maximum performance, which is generally a good thing.

source ~/.bashrc (OR source ~/ros2_ws/install/setup.bash)

Just to make sure everything is nice and clean, do a new build in a fresh terminal window:

cd ~/ros2_ws/
colcon build
source ~/.bashrc (OR source ~/ros2_ws/install/setup.bash)

Fix Other Issues

The pick and place demo works during the planning phase but fails during execution. This issue has been documented at this link. If you execute the plan via RViz, everything will work fine. If you execute it via the code, execution fails. The error you will see is this: “Stopping execution because the path to execute became invalid(probably the environment changed)”

To fix this issue, you need to go to this file:

cd ~/ros2_ws/src/moveit_task_constructor/core/src/
gedit storage.cpp

Change this line:

if (this->end()->scene()->getParent() == this->start()->scene())
	this->end()->scene()->getPlanningSceneDiffMsg(t.scene_diff);
else
	this->end()->scene()->getPlanningSceneMsg(t.scene_diff);

To this:

this->end()->scene()->getPlanningSceneDiffMsg(t.scene_diff);
cd ~/ros2_ws/
colcon build
source ~/.bashrc (OR source ~/ros2_ws/install/setup.bash)

Congratulations! You have now successfully installed the MoveIt Task Constructor.

Create a Package for Your MTC Code

Now that we have installed the MTC, let’s create a package to store our code.

MoveIt Task Constructor includes several demo programs. We will recreate these demos from scratch in future tutorials. For now, let’s just create a package  to hold the launch files for these demo programs.

Create a Package

cd ~/ros2_ws/src/mycobot_ros2/
ros2 pkg create --build-type ament_cmake --dependencies generate_parameter_library moveit_core moveit_ros_planning_interface moveit_task_constructor_core rclcpp --license BSD-3-Clause --node-name mtc_node hello_moveit_task_constructor

Create a Launch File for the Demos

Move inside the package.

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit_task_constructor/

Create a folder named launch.

mkdir launch

Now let’s add a launch file:

cd launch
gedit run.launch.py 

Add this code:

# Author: Addison Sears-Collins
# Date: August 26, 2024
# Description: ROS 2 launch file for MoveIt Task Constructor demo nodes.

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from moveit_configs_utils import MoveItConfigsBuilder
 

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'
    package_name_mtc = 'hello_moveit_task_constructor'

    # 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)
    pkg_share_mtc = FindPackageShare(package=package_name_mtc).find(package_name_mtc)

    # 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'
    mtc_node_params_file_path = 'config/mtc_node_params.yaml'

    # 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)
    mtc_node_params_file_path = os.path.join(pkg_share_mtc, mtc_node_params_file_path)

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

    # 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_exe_cmd = DeclareLaunchArgument(
        name="exe",
        default_value="pick_place_demo",
        description="Which demo to run",
        choices=["alternative_path_costs", "cartesian", "fallbacks_move_to", 
                 "ik_clearance_cost", "modular", "mtc_node", "pick_place_demo"])
  
    # 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)
        .robot_description_semantic(file_path=srdf_model_path)
        .trajectory_execution(file_path=moveit_controllers_file_path)
        .joint_limits(file_path=joint_limits_file_path)
        .robot_description_kinematics(file_path=kinematics_file_path)
        .pilz_cartesian_limits(file_path=pilz_cartesian_limits_file_path)
        .planning_pipelines(
            pipelines=["ompl", "pilz_industrial_motion_planner", "stomp"],
            default_planning_pipeline="ompl"
        )
        .planning_scene_monitor(
            publish_robot_description=False,
            publish_robot_description_semantic=True,
            publish_planning_scene=True,
        )
        .to_moveit_configs()
    )
    
    node = Node(
        package="hello_moveit_task_constructor",
        executable=exe,
        output="screen",
        parameters=[
            moveit_config.robot_description,
            moveit_config.robot_description_semantic,
            moveit_config.robot_description_kinematics,
            moveit_config.joint_limits,
            moveit_config.pilz_cartesian_limits,
            moveit_config.planning_pipelines,
            {'use_sim_time': use_sim_time},
            mtc_node_params_file_path,
        ],
    )

    # Create the launch description and populate
    ld = LaunchDescription()

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

    # Add any actions
    ld.add_action(node)

    return ld

Save the file, and close it.

gedit demo.launch.py 

Add this code:

# Author: Addison Sears-Collins
# Date: August 15, 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/mtc.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="ompl"
        )
        .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()
    )

    # Enable the execution of tasks in the MoveIt Task Constructor (MTC).
    move_group_capabilities = {"capabilities": "move_group/ExecuteTaskSolutionCapability"}
    
    # 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}},
            move_group_capabilities,
        ],
    )

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

Create an Include Folder

Let’s add an include folder for our C++ header files.

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit_task_constructor/
mkdir -p include/hello_moveit_task_constructor
cd include/hello_moveit_task_constructor
gedit pick_place_task.h

Add this code:

Don’t worry about what the code means for now. We will go through it in a future tutorial.

Save the file, and close it.

Create an RViz Config File

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config_manual_setup/rviz/
gedit mtc.rviz

Add this code.

Save the file, and close it.

Add Demonstration Code

cd ~/ros2_ws/src/mycobot_ros2/hello_moveit_task_constructor/src/

Add all the files you see in this directory into the src folder.

Edit CMakeLists.txt

Now let’s edit CMakeLists.txt.

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

Add this code.

Save the file, and close it.

Edit package.xml

Now let’s edit the package.xml file.

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

Add this code.

Save the file, and close it.

Build the Package

Now let’s build.

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

That’s it! You are now ready to start building your own applications. We will do just that in the following tutorials. Keep building!