Skip to main content
Version: 8

Complete config.yaml Reference Guide

This guide provides comprehensive documentation for all configuration options available in MoveIt Pro's config.yaml files. Each robot configuration package requires a config/config.yaml file that defines various settings for robot description, motion planning, control, and Behaviors.

tip

For a step-by-step how-to-guide on creating a custom robot configuration, see Creating a Custom Robot Configuration.

For example config.yaml files, please check out our MoveIt Pro example workspace repository.

MoveIt Pro's configuration system supports hierarchical inheritance through the based_on_package field, allowing you to extend existing configurations while overriding specific settings.

The main configuration sections are:

  1. based_on_package - Configuration inheritance
  2. hardware - Robot description and hardware settings
  3. moveit_params - MoveIt configuration parameters
  4. ros2_control - ROS 2 control configuration
  5. objectives - Behaviors and Objectives configuration
  6. ros_global_params - Global ROS parameter overrides

Configuration Inheritance

based_on_package

Type: string (optional) Description: Specifies a parent robot configuration package to inherit settings from. This enables configuration hierarchies where specialized configurations can extend base configurations.

For an example of configuration inheritance, see the lab_sim config.yaml which inherits from the UR5e base configuration.

When inheritance is used, settings in the current configuration override corresponding settings from the parent configuration. Lists and dictionaries are merged, with the child configuration taking precedence for conflicting keys.

Hardware Configuration

hardware

Type: object (required) Description: Defines robot description, hardware drivers, and simulation settings.

hardware.launch_control_node

Type: boolean (optional, default: true) Description: Whether to launch the ros2_control node. Set this to false if another process manages the control node.

hardware:
launch_control_node: true

hardware.launch_robot_state_publisher

Type: boolean (optional, default: true) Description: Whether to launch the robot state publisher node.

hardware:
launch_robot_state_publisher: true

hardware.robot_description

Type: object (required) Description: Defines the robot's URDF and SRDF files, plus optional parameters.

hardware.robot_description.urdf

Type: object (required) Description: Location of the robot's URDF or XACRO file.

hardware:
robot_description:
urdf:
package: "my_robot_config"
path: "description/my_robot.xacro"
  • package (string, required): ROS package containing the URDF/XACRO file
  • path (string, required): Relative path within the package
hardware.robot_description.srdf

Type: object (required) Description: Location of the robot's Semantic Robot Description Format (SRDF) file.

hardware:
robot_description:
srdf:
package: "my_robot_config"
path: "config/moveit/my_robot.srdf"
  • package (string, required): ROS package containing the SRDF file
  • path (string, required): Relative path within the package
hardware.robot_description.urdf_params

Type: array (optional) Description: Xacro arguments passed to your specified urdf for use with Xacro generation. Each array element is a dictionary with argument name-value pairs.

hardware:
robot_description:
urdf_params:
- name: "ur5e"
- prefix: ""
- safety_limits: true
- safety_pos_margin: 0.15
- safety_k_position: 20
- mujoco_model: "description/scene.xml"

hardware.robot_driver_persist_launch_file

Type: object (optional, default: blank.launch.py spins up no new processes) Description: Launch file for robot drivers that should stay active for the entire MoveIt Pro session (real hardware).

hardware:
robot_driver_persist_launch_file:
package: "my_robot_driver"
path: "launch/robot_driver.launch.py"

hardware.simulated

Type: boolean (optional, default: false) Description: Whether the system is running in simulation mode. Affects which launch files are used.

hardware:
simulated: true

hardware.simulated_hardware_launch_file

Type: object (optional, default: blank.launch.py spins up no new processes) Description: Launch file for the simulation backend (e.g., MuJoCo, Gazebo).

hardware:
simulated_hardware_launch_file:
package: "my_simulation"
path: "launch/mujoco_simulation.launch.py"

hardware.simulated_robot_driver_persist_launch_file

Type: object (optional, default: blank.launch.py spins up no new processes) Description: Launch file for simulated robot drivers that should stay active during simulation.

hardware:
simulated_robot_driver_persist_launch_file:
package: "my_robot_sim"
path: "launch/simulated_drivers.launch.py"

Motion and Planning Configuration Parameters

moveit_params

Type: object (required) Description: Configuration parameters for MoveIt Pro motion planning, kinematics, and related components.

moveit_params.joint_group_name

Type: string (required) Description: Primary joint group name used by the Waypoint Manager and motion planning.

moveit_params:
joint_group_name: "manipulator"

moveit_params.kinematics

Type: object (optional) Description: Kinematics solver configuration for motion planning.

moveit_params:
kinematics:
package: "my_robot_config"
path: "config/moveit/kinematics.yaml"

Example kinematics.yaml content:

manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.05

moveit_params.joint_limits

Type: object (optional) Description: Joint limits for motion planning (position, velocity, acceleration, jerk).

moveit_params:
joint_limits:
package: "my_robot_config"
path: "config/moveit/joint_limits.yaml"

Example joint_limits.yaml content:

joint_limits:
shoulder_pan_joint:
has_velocity_limits: true
max_velocity: 3.14159
has_acceleration_limits: true
max_acceleration: 5.0

moveit_params.servo

Type: object (optional) Description: Configuration for MoveIt Servo (real-time teleoperation).

note

Deprecated: The moveit_params.servo section is deprecated and will be removed in a future release. Please use alternative teleoperation methods instead of MoveIt Servo.

moveit_params:
servo:
package: "my_robot_config"
path: "config/moveit/servo.yaml"

Example servo.yaml content:

move_group_name: manipulator
planning_frame: base_link
ee_frame_name: tool0
command_in_type: "unitless"
scale:
linear: 0.4
rotational: 0.8

moveit_params.servo_joint_limits

Type: object (optional) Description: Separate joint limits specifically for servo operation. If not specified, uses regular joint limits.

note

Deprecated: The moveit_params.servo_joint_limits section is deprecated and will be removed in a future release. MoveIt Servo is being phased out in favor of other teleoperation methods. Please update your configuration accordingly.

moveit_params:
servo_joint_limits:
package: "my_robot_config"
path: "config/moveit/servo_joint_limits.yaml"

moveit_params.pose_jog

Type: object (optional) Description: Configuration for pose jogging functionality.

moveit_params:
pose_jog:
package: "my_robot_config"
path: "config/moveit/pose_jog.yaml"

Example pose_jog.yaml content:

planning_groups: ["manipulator"]
controllers: ["joint_trajectory_controller"]
warning

The planning_groups and controllers arrays must have the same length - each planning group must correspond to a controller.

moveit_params.sensors_3d

Type: object (optional) Description: Configuration for 3D sensors and point cloud processing.

moveit_params:
sensors_3d:
package: "my_robot_config"
path: "config/moveit/sensors_3d.yaml"

Example sensors_3d.yaml content:

sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /camera/depth/color/points
max_range: 5.0
point_subsample: 1

moveit_params.ompl_planning

Type: object (optional) Description: OMPL (Open Motion Planning Library) planner configuration.

moveit_params:
ompl_planning:
package: "my_robot_config"
path: "config/moveit/ompl_planning.yaml"

Example ompl_planning.yaml content:

planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/FixWorkspaceBounds
response_adapters: >-
default_planner_response_adapters/AddTimeOptimalParameterization

moveit_params.stomp_planning

Type: object (optional) Description: STOMP (Stochastic Trajectory Optimization for Motion Planning) configuration.

note

STOMP planning configuration is optional and not required for basic MoveIt Pro functionality.

moveit_params:
stomp_planning:
package: "my_robot_config"
path: "config/moveit/stomp_planning.yaml"

moveit_params.moveit_simple_controller_manager

Type: object (optional) Description: Configuration for MoveIt's simple controller manager. You would only configure this if you have actuators you won't control via the ros2_control framework. For details, see Creating a Custom Robot Controller.

moveit_params:
moveit_simple_controller_manager:
package: "my_robot_config"
path: "config/moveit/controllers.yaml"

moveit_params.trajectory_execution

Type: object (optional) Description: Trajectory execution parameters for MoveIt.

moveit_params:
trajectory_execution:
manage_controllers: true
allowed_execution_duration_scaling: 2.0
allowed_goal_duration_margin: 5.0
allowed_start_tolerance: 0.01
control_multi_dof_joint_variables: false
  • manage_controllers (boolean): Whether MoveIt should manage controller activation
  • allowed_execution_duration_scaling (number): Maximum scaling factor for trajectory execution time
  • allowed_goal_duration_margin (number): Additional time margin for trajectory completion
  • allowed_start_tolerance (number): Tolerance for starting joint positions
  • control_multi_dof_joint_variables (boolean, optional): Whether to control multi-DOF joints

moveit_params.publish

Type: object (optional) Description: Configuration for what information MoveIt publishes.

moveit_params:
publish:
planning_scene: true
geometry_updates: true
state_updates: true
transforms_updates: true
  • planning_scene (boolean): Publish planning scene updates
  • geometry_updates (boolean): Publish geometry changes
  • state_updates (boolean): Publish robot state updates
  • transforms_updates (boolean): Publish transform updates

ROS 2 Control Configuration

ros2_control

Type: object (required if using ros2_control) Description: Configuration for ros2_control controllers and hardware interfaces.

ros2_control.config

Type: object (required) Description: Location of the ros2_control configuration file.

ros2_control:
config:
package: "my_robot_config"
path: "config/control/my_robot.ros2_control.yaml"

ros2_control.controllers_active_at_startup

Type: array (optional, default: []) Description: List of controllers to load and activate when MoveIt Pro starts.

ros2_control:
controllers_active_at_startup:
- "joint_state_broadcaster"
- "joint_trajectory_controller"
- "force_torque_sensor_broadcaster"
- "robotiq_gripper_controller"

ros2_control.controllers_inactive_at_startup

Type: array (optional, default: []) Description: List of controllers to load but not activate at startup (can be activated later).

ros2_control:
controllers_inactive_at_startup:
- "servo_controller"
- "joint_trajectory_admittance_controller"
- "velocity_force_controller"

ros2_control.controllers_not_managed

Type: array (optional, default: []) Description: List of controllers that MoveIt Pro should not spawn or manage.

ros2_control:
controllers_not_managed:
- "external_controller"

ros2_control.controller_shared_topics

Type: array (optional, default: []) Description: Topic remapping configuration for sharing topics between controllers.

ros2_control:
controller_shared_topics:
/joint_commands:
- "/controller1/joint_commands"
- "/controller2/joint_commands"

Objectives and Behaviors Configuration

objectives

Type: object (required) Description: Configuration for MoveIt Pro Behaviors, Objectives, and waypoints.

objectives.behavior_loader_plugins

Type: object (required) Description: Dictionary mapping plugin names to lists of Behavior loader classes.

objectives:
behavior_loader_plugins:
core:
- "moveit_studio::behaviors::CoreBehaviorsLoader"
- "moveit_studio::behaviors::MTCCoreBehaviorsLoader"
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
custom:
- "my_custom_package::behaviors::CustomBehaviorsLoader"

Each key must be unique across the configuration hierarchy. Common core loaders include:

  • CoreBehaviorsLoader: Basic motion and control Behaviors
  • MTCCoreBehaviorsLoader: MoveIt Task Constructor Behaviors
  • ServoBehaviorsLoader: Real-time servo Behaviors
  • VisionBehaviorsLoader: Computer vision and perception Behaviors
  • ConverterBehaviorsLoader: Packing, unpacking, and transforming messages via Behaviors

objectives.objective_library_paths

Type: object (required) Description: Dictionary mapping library names to package locations containing Objective XML files.

objectives:
objective_library_paths:
core_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/core"
motion_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/motion"
perception_objectives:
package_name: "moveit_pro_objectives"
relative_path: "objectives/perception"
custom_objectives:
package_name: "my_robot_config"
relative_path: "objectives"

Each objective library entry requires:

  • package_name (string): ROS package containing objectives
  • relative_path (string): Path within the package to Objectives directory
note

The last entry in the list will be the location where newly created Objectives are saved.

objectives.waypoints_file

Type: object (required) Description: Location of the waypoints YAML file for named robot poses.

objectives:
waypoints_file:
package_name: "my_robot_config"
relative_path: "waypoints/waypoints.yaml"
  • package_name (string): ROS package containing waypoints file
  • relative_path (string): Path within package to waypoints file

Global ROS Parameters

ros_global_params

Type: object (optional) Description: Global ROS parameter overrides that apply to all nodes launched by MoveIt Pro.

ros_global_params:
use_sim_time: true
robot_description_timeout: 10.0
custom_parameter: "custom_value"

Common global parameters:

  • use_sim_time (boolean): Whether to use simulation time
  • robot_description_timeout (number): Timeout for robot description loading

Configuration Validation

MoveIt Pro validates configuration files using Pydantic models. Common validation errors include:

Missing Required Fields

# ERROR: Missing required 'hardware' section
objectives:
behavior_loader_plugins: {}

Extra/Unknown Fields

# ERROR: 'unknown_field' is not allowed
hardware:
unknown_field: "value" # This will cause validation to fail

Type Mismatches

# ERROR: Expected boolean, got string
hardware:
simulated: "true" # Should be: true (boolean)

Invalid File References

# ERROR: Package or file not found
hardware:
robot_description:
urdf:
package: "nonexistent_package"
path: "missing_file.urdf"

This reference guide covers all major configuration options available in MoveIt Pro's config.yaml files. For implementation examples and step-by-step instructions, refer to the specific configuration tutorials in this documentation section.