Skip to main content
Version: 9

Migrate User Workspace From 8.x to 9.0

MoveIt Pro 9.0 introduces significant architectural and workflow improvements, and this migration guide is designed to help existing users update their systems smoothly and with confidence.

Migration Summary

Migrating a standard 8.x workspace to 9.0 is mostly a terminology and Behavior Tree (XML) update. Complete the Required Migration Changes for a minimal migration through the breaking changes. Complete the Recommended 9.0 Enhancements to adopt the updated execution and teleoperation workflows.

Required Migration Changes

Host Hardware Access

Responsibility for exposing host hardware has moved from the MoveIt Pro Docker Compose file to the user workspace Docker Compose file.

For services needing host hardware access, map devices in your docker-compose.yaml:

services:

base: {}

agent_bridge: {}

drivers: # most likely to need host hardware access
volumes:
- /dev/i2c-9:/dev/i2c-9
- /dev/ttyACM0:/dev/ttyACM0

web_ui: {}

dev:
volumes:
- /dev/i2c-9:/dev/i2c-9
- /dev/ttyACM0:/dev/ttyACM0

Renaming and Compatibility Updates

This section contains all required naming and compatibility changes for a standard workspace migration. Whenever possible, a sed command is provided to make the appropriate changes in the workspace of a Linux system. Please run these commands from the top level of your user workspace, ~/moveit_pro/moveit_pro_example_ws/ for example.

Environment Variable and Base Image Renames

In version 9.0, environment variables were renamed for more platform-wide consistency:

  • STUDIO_USERNAME -> MOVEIT_USERNAME
  • STUDIO_USER_UID -> MOVEIT_USER_UID
  • STUDIO_USER_GID -> MOVEIT_USER_GID
  • STUDIO_DOCKER_TAG -> MOVEIT_DOCKER_TAG
  • STUDIO_LICENSE_KEY -> MOVEIT_LICENSE_KEY

Use this command to update:

sed -i 's/MOVEIT_STUDIO_BASE_IMAGE/MOVEIT_PRO_BASE_IMAGE/g' Dockerfile
for file in $(grep -r 'STUDIO_' -l); do
sed -i 's/STUDIO_/MOVEIT_/g' $file;
done
tip

MoveIt Pro configuration files outside a workspace are automatically migrated during the 9.0 installation process.

Include File Rename

The include path for MTC-related code changed from moveit/task_constructor to moveit_pro/task_constructor:

for file in $(grep -r -l -E 'include ["|<]moveit\/task_constructor'); do
sed -i -E 's/include (["|<])moveit\/task_constructor/include \1moveit_pro\/task_constructor/g' $file
done

Package Name Changes

The following packages were renamed and bash scripts are included below which will automatically apply the renames to your user workspace when run inside of it:

moveit_studio_behavior_interface -> moveit_pro_behavior_interface (do before moveit_studio_behavior)

for file in $(grep -r -l 'moveit_studio_behavior_interface'); do
sed -i 's/moveit_studio_behavior_interface/moveit_pro_behavior_interface/g' $file
done

moveit_studio_behavior -> moveit_pro_behavior

for file in $(grep -r -l 'moveit_studio_behavior'); do
sed -i 's/moveit_studio_behavior/moveit_pro_behavior/g' $file
done

Namespace Changes

moveit_studio::behaviors -> moveit_pro::behaviors

for file in $(grep -r -l 'moveit_studio::behaviors'); do
sed -i 's/moveit_studio::behaviors/moveit_pro::behaviors/g' $file
done

moveit::task_constructor -> moveit_pro::task_constructor

for file in $(grep -r -l 'moveit::task_constructor'); do
sed -i 's/moveit::task_constructor/moveit_pro::task_constructor/g' $file
done

Set ROS_DISTRO in Dockerfile

To support multi-distribution image tagging, update your Dockerfile base image argument:

sed -i 's#^ARG MOVEIT_PRO_BASE_IMAGE=picknikciuser/moveit-studio:${MOVEIT_DOCKER_TAG:-main}$#ARG MOVEIT_PRO_BASE_IMAGE=picknikciuser/moveit-studio:${MOVEIT_DOCKER_TAG:-main}-${MOVEIT_ROS_DISTRO:-humble}#' Dockerfile

Migrating GetContourFromPointCloudSlice Parameter

The GetContourFromPointCloudSlice Behavior has renamed its input port from desired_pose_spacing to max_pose_spacing to better reflect its actual behavior. This parameter sets an upper limit on the distance between consecutive waypoints—it adds interpolated waypoints when gaps are too large but preserves existing waypoints that are closer together to maintain contour accuracy.

If you have custom Objectives using this Behavior, update the port name in your XML files:

Replace:

<Action
ID="GetContourFromPointCloudSlice"
desired_pose_spacing="0.1"
...other ports...
/>

With:

<Action
ID="GetContourFromPointCloudSlice"
max_pose_spacing="0.1"
...other ports...
/>

The semantics and default value (0.1 meters) remain unchanged—only the port name has been updated for clarity.

Migrating GetImage, GetCameraInfo, GetPointCloud Parameter

If you have custom Objectives using GetImage, GetCameraInfo, or GetPointCloud Behaviors, rename the timeout_sec port to message_timeout_sec in your XML files.

MPC Name Changes

MPC Behaviors (which currently include point cloud clearance, pose tracking, and sphere clearance), along with their header, .cpp, and test files, are now located under their own mpc folder. To use these Behaviors, add the following line to your configuration file:

moveit_pro::behaviors::MPCBehaviorsLoader

Controller Name Changes

We have removed the artificial prepending of slashes in controller names, meaning all controller names should be written as they are defined in the ros2_control config. For example, if your controller is defined as joint_velocity_controller, you should use that exact name in any Behavior taking a controller name, instead of /joint_velocity_controller.

Docker Image Name Changes

  • Docker images specific to the NVIDIA Jetson Orin have changed tags from X.Y.Z-arm64-jetson36.4 to X.Y.Z-jetson-cuda12.6-cudnn9. If you use platform-specific Docker image names in your user workspace, please update accordingly.
  • All Docker image names now include the ROS distribution which they target after the version or branch (e.g. main becomes main-humble). If you manually supply Docker image names in your user workspace (not recommended), please update accordingly.

Removed Behaviors

Several previously deprecated Behaviors were removed in 9.0. If your custom Objectives still use them, replace them according to this table:

Behavior NameRecommended Replacement
ActivateControllersUse SwitchControllers
AddSubframeToObjectUse PoseStamped-related Behaviors
AddToolToSceneUse AddURDF
AppendOrientationConstraintOrientation constraints are now embedded as input ports in all planning Behaviors
AttachToolUse AttachURDF
DetachToolUse DetachURDF or RemoveURDFFromScene
GenerateObjectsInBoxObjects can be created directly in the simulated environment as needed
GetGraspAndTwistSubframesUse pose-manipulation Behaviors such as PlanCartesianPath or PlanMoveToPose
GetMoveAlongArcSubframesUse pose-manipulation Behaviors such as PlanCartesianPath or PlanMoveToPose
InitializeMotionConstraintsOrientation constraints are now embedded as input ports in all planning Behaviors
LoadObjectiveParametersAll Behavior parameters are now always set as input ports
RemoveToolFromSceneUse DetachURDF or RemoveURDFFromScene
ServoTowardsPoseUse PoseJog
SetupMTCApproachGraspUse SetupMTCMoveAlongFrameAxis
SetupMTCGenerateCuboidGraspsUse GenerateCuboidGraspPoses
SetupMTCGenerateVacuumGraspsUse GenerateVacuumGraspPoses
SetupMTCRetractFromGraspUse SetupMTCMoveAlongFrameAxis
TeleoperateTwistUse PoseJog
TransformPoseFromYamlUse LoadPoseStampedFromYaml with TransformPoseWithPose
WriteCalibratedPoseToYamlUse SaveToYaml

Servo Deprecation

MoveIt Servo-based teleoperation is deprecated in this migration path in favor of the Cartesian and Joint controllers, velocity_force_controller and joint_velocity_controller respectively. If your workspace still references Servo, remove all Servo-related details from your robot config package as they are no longer used. Servo can still be used with MoveIt Pro if built and launched separately, but is no longer packaged with MoveIt Pro.

Please do the following:

  1. (Required) Remove ServoBehaviorsLoader entries from behavior_loader_plugins in config.yaml.
  2. Remove the block that points to config/moveit/servo.yaml from config.yaml.
  3. Remove "servo_controller" from controllers_inactive_at_startup in config.yaml.
  4. Delete config/moveit/servo.yaml from the robot config package (or keep it unused).

Example config/config.yaml cleanup:

# Remove commented section from moveit_params:
moveit_params:
# servo:
# package: "your_package_name"
# path: "config/moveit/servo.yaml"

# Remove commented section from controller lists:
ros2_control:
controllers_inactive_at_startup:
# - "servo_controller"
- "velocity_force_controller"
- "joint_velocity_controller"

# Remove commented lines from behavior loader plugins:
objectives:
behavior_loader_plugins:
core:
# - "moveit_studio::behaviors::ServoBehaviorsLoader"
# - "moveit_pro::behaviors::ServoBehaviorsLoader"

These updates are not strictly required for compatibility, but they align your workspace with the default 9.0 workflows and are strongly recommended.

Configure Joint Jog for Teleoperation

MoveIt Pro 9.0 replaces Servo with a new Joint Jog teleoperation mode that enables direct joint control from the Web UI with improved performance and safety.

Create Joint Jog Configuration File

Create a new file config/moveit/joint_jog.yaml in your robot configuration package:

# Planning groups to use in JointJog, and their corresponding JVC controllers.
# The number of elements in `planning_groups` and `controllers` must match.
planning_groups: ['manipulator']
controllers: ['joint_velocity_controller']

For multi-arm configurations, list all planning groups and their corresponding controllers:

planning_groups: ['left_manipulator', 'right_manipulator']
controllers: ['left_joint_velocity_controller', 'right_joint_velocity_controller']

Reference Joint Jog Config in Main Config

Add the joint_jog parameter to your config/config.yaml under moveit_params:

moveit_params:
# ... existing parameters ...
joint_jog:
package: "your_package_name"
path: "config/moveit/joint_jog.yaml"

Configure Joint Velocity Controller

Add a Joint Velocity Controller configuration to your ros2_control.yaml file. This controller handles the low-level joint command execution with safety limits:

controller_manager:
ros__parameters:
# ... existing controllers ...
joint_velocity_controller:
type: joint_velocity_controller/JointVelocityController

joint_velocity_controller:
ros__parameters:
# Joint group to control
planning_group_name: manipulator
# Maximum joint-space velocities (rad/s) - one value per joint
max_joint_velocity:
- 1.0
- 1.0
- 1.0
- 1.0
- 1.0
- 1.0
# Maximum joint-space accelerations (rad/s²) - one value per joint
max_joint_acceleration:
- 2.0
- 2.0
- 2.0
- 2.0
- 2.0
- 2.0
# Command interface type: "position" or "velocity"
command_interfaces: ["position"]
# Safety margin for joint position limits (radians)
joint_limit_position_tolerance: 0.02
# Timeout after which controller stops if no commands received (seconds)
command_timeout: 0.2
# Controller state publishing rate (Hz)
state_publish_rate: 20

Important: Adjust max_joint_velocity and max_joint_acceleration values based on your robot's capabilities and safety requirements. The values shown are conservative defaults.

Add Controller to Inactive Controllers List

Add the Joint Velocity Controller to controllers_inactive_at_startup in config/config.yaml:

ros2_control:
# ... existing configuration ...
controllers_inactive_at_startup:
- "velocity_force_controller"
- "joint_velocity_controller" # Add this line

This ensures the controller is loaded but not active until teleoperation mode is engaged.

Update your Request Teleoperation Objective to use Joint Jog

If your config overrides the default Request Teleoperation Objective, update it to use the new Joint Jog Behavior instead of the deprecated Servo-based Behavior. For that, replace any instance of TeleoperateJointJog with JointJog, and use SwitchControllers to enable the joint_velocity_controller when starting teleoperation. Take a look at the default Request Teleoperation Objective for reference.

Notes

  • Include the objectives folder of the moveit_pro_objectives package in your config.yaml objective_library_paths to use default Objectives, and avoid overriding them if possible (remove them from your workspace).
  • For general one-arm robots, check out our lab_sim example for reference.
  • For robots with mobile bases, configure command_joints to include platform joints and set command_interfaces: ["velocity"]. See our hangar_sim example for reference.
  • For dual-arm or multi-arm systems, create separate controller instances for each arm with unique names (e.g., left_joint_velocity_controller, right_joint_velocity_controller). See our dual_arm_sim example for reference.
  • The Joint Velocity Controller includes built-in safety features such as joint limit checking, collision avoidance (when enabled), and automatic stopping on command timeout.

JTAC as Default Execution Pipeline

MoveIt Pro now uses the Joint Trajectory Admittance Controller (JTAC) as the default execution pipeline for motion objectives. This provides improved force-sensitive trajectory execution while still supporting non-admittance motion control for systems that are not force-aware.

Behavior Consolidation

ExecuteTrajectory Behavior

ExecuteFollowJointTrajectory and ExecuteTrajectoryWithAdmittance were consolidated into ExecuteTrajectory, which supports both:

  • JTC-like FollowJointTrajectory action servers via execution_pipeline="jtc"
  • JTAC action servers via execution_pipeline="jtac" (default)
Execute MTC Solution Subtree

ExecuteMTCTask is deprecated in favor of ExecuteMTCSolution, which allows both JTC and JTAC controllers to execute MTC solutions.

A new reusable subtree Execute MTC Solution encapsulates controller switching and MTC solution execution for both JTAC and JTC-like pipelines. Execute MTC Solution (JTC) is also available as a convenience wrapper.

Modified Core Objectives

Core Objectives updated to default to JTAC:

Move to Pose
  • Uses ExecuteMTCSolution instead of ExecuteMTCTask
  • Uses Execute MTC Solution internally
  • New input ports: execution_pipeline, controller_action_name
  • Default execution_pipeline: "jtac"
  • Default controller_action_name: "/joint_trajectory_admittance_controller/follow_joint_trajectory"
  • Default controller_names: "joint_trajectory_admittance_controller"
  • Move to Pose (JTC) convenience variant available
Move to Joint State
  • Uses ExecuteTrajectory
  • New input port: execution_pipeline (default "jtac")
  • Default controller_names: "joint_trajectory_admittance_controller"
  • Default controller_action_server: "/joint_trajectory_admittance_controller/follow_joint_trajectory"
Interpolate to Joint State
  • Uses ExecuteTrajectory
  • New input port: execution_pipeline (default "jtac")
  • Default controller_names: "joint_trajectory_admittance_controller"
  • Default controller_action_server: "/joint_trajectory_admittance_controller/follow_joint_trajectory"
Move to Waypoint
  • Uses Move to Joint State internally
  • New input port: execution_pipeline (default "jtac")
  • Default controller_names: "joint_trajectory_admittance_controller"
  • Default controller_action_server: "/joint_trajectory_admittance_controller/follow_joint_trajectory"
  • Move to Waypoint (JTC) convenience variant available
Request Teleoperation
  • Updated for JTAC execution pipeline
  • New input port: execution_pipeline (default "jtac")
  • Default controller_action_server: "/joint_trajectory_admittance_controller/follow_joint_trajectory"
  • Default joint_trajectory_controller_name: "joint_trajectory_admittance_controller"

Migration for Users Adopting JTAC

To use JTAC, first configure a Joint Trajectory Admittance Controller in your robot configuration package. See Configure Admittance Controller for setup details.

Once configured, use core Objective defaults or override names as needed.

Migrating ExecuteTrajectoryWithAdmittance

Replace:

<Action
ID="ExecuteTrajectoryWithAdmittance"
execute_trajectory_with_admittance_action_name="{controller_action_server}"
joint_trajectory_msg="{joint_trajectory_msg}"
admittance_parameters_msg="{admittance_parameters}"
/>

With:

<Action
ID="ExecuteTrajectory"
execution_pipeline="jtac"
controller_action_name="{controller_action_server}"
joint_trajectory_msg="{joint_trajectory_msg}"
admittance_parameters_msg="{admittance_parameters}"
/>
Customizing Admittance Parameters

Pass additional parameters to Execute MTC Solution or ExecuteTrajectory:

<SubTree
ID="Execute MTC Solution"
solution="{your_mtc_solution}"
execution_pipeline="jtac"
controller_names="joint_trajectory_admittance_controller"
controller_action_name="/joint_trajectory_admittance_controller/follow_joint_trajectory"
admittance_parameters_msg="{your_admittance_params}"
goal_position_tolerance="0.01"
path_position_tolerance="0.02"
absolute_force_torque_threshold="{your_force_limits}"
/>

Controller Configuration Update

joints and base_frame parameters were removed from:

  • joint_trajectory_admittance_controller
  • velocity_force_controller

These are now derived from planning_group_name.

Steps:

  1. Remove joints and its list.
  2. Remove base_frame.
  3. Add planning_group_name set to your planning group.

Example:

Before:

joint_trajectory_admittance_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
# other joints
base_frame: base_link
sensor_frame: tool0
ee_frame: tool0
# ... other parameters

After:

joint_trajectory_admittance_controller:
ros__parameters:
planning_group_name: manipulator
sensor_frame: tool0
ee_frame: tool0
# ... other parameters

Migration for Users Continuing with JTC-like Controllers

If you still use JTC-like controllers, update custom Objectives as follows.

Migrating ExecuteFollowJointTrajectory

Replace:

<Action
ID="ExecuteFollowJointTrajectory"
execute_follow_joint_trajectory_action_name="{controller_action_server}"
joint_trajectory_msg="{joint_trajectory_msg}"
/>

With:

<Action
ID="ExecuteTrajectory"
execution_pipeline="jtc"
controller_action_name="{controller_action_server}"
joint_trajectory_msg="{joint_trajectory_msg}"
/>

Key changes:

  • Use the new ExecuteTrajectory behavior
  • Set execution_pipeline to "jtc" for standard JTC-like controllers
  • Rename execute_follow_joint_trajectory_action_name to controller_action_name

Migrating ExecuteMTCTask

Replace:

<Action
ID="ExecuteMTCTask"
solution="{solution}"
goal_duration_tolerance="-1.0"
/>

With:

<SubTree
ID="Execute MTC Solution"
solution="{solution}"
execution_pipeline="jtc"
controller_names="joint_trajectory_controller"
controller_action_name="/joint_trajectory_controller/follow_joint_trajectory"
<!-- ... other parameters ... -->
/>

Overriding Core Objective Defaults

When calling core Objectives, override these input ports to use JTC:

Move to Pose:

<SubTree
ID="Move to Pose"
execution_pipeline="jtc"
controller_action_name="/joint_trajectory_controller/follow_joint_trajectory"
controller_names="joint_trajectory_controller"
<!-- ... other parameters ... -->
/>

Move to Joint State:

<SubTree
ID="Move to Joint State"
execution_pipeline="jtc"
controller_action_server="/joint_trajectory_controller/follow_joint_trajectory"
controller_names="joint_trajectory_controller"
<!-- ... other parameters ... -->
/>

Interpolate to Joint State:

<SubTree
ID="Interpolate to Joint State"
execution_pipeline="jtc"
controller_action_server="/joint_trajectory_controller/follow_joint_trajectory"
controller_names="joint_trajectory_controller"
<!-- ... other parameters ... -->
/>

Move to Waypoint:

<SubTree
ID="Move to Waypoint"
execution_pipeline="jtc"
controller_action_server="/joint_trajectory_controller/follow_joint_trajectory"
controller_names="joint_trajectory_controller"
<!-- ... other parameters ... -->
/>

Request Teleoperation:

<SubTree
ID="Request Teleoperation"
execution_pipeline="jtc"
controller_action_server="/joint_trajectory_controller/follow_joint_trajectory"
joint_trajectory_controller_name="joint_trajectory_controller"
<!-- ... other parameters ... -->
/>

Optional Adjustments

Default Value Changes

  • The default value for require_user_approval in the Move to Pose Objective has been changed from true to false. This means that by default, the Objective will execute trajectories without requiring user approval (No Preview mode). If you need the previous behavior where user approval is required, explicitly set require_user_approval="true" in your Objective configuration.