Skip to main content
Version: 9

moveit_params Values

Motion and Planning Configuration Parameters

example_robot_ws Checkpoint

If you are following this guide with example_robot_ws, your workspace should look like branch step5. We are now editing example_robot_mock config.yaml.

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

Description: Kinematics solver configuration for motion planning.

moveit_params:
kinematics:
package: "example_robot_mock"
path: "config/moveit/pose_ik.yaml"

Your moveit_params.kinematics should define an IK solver for each planning group in your hardware.robot_description.srdf you plan to use.

PoseIK Solve Modes

PoseIK is a highly efficient implementation of a Jacobian-based Newton-Raphson Inverse Kinematics Solver for MoveIt Pro. The solver shows significant performance gains compared to KDL and TRAC_IK.

For more information on PoseIK and configuration options, refer to the Planners and Solvers Concept guide.

  • first_found: In this mode the solver will return as soon as a solution is found. It won't try to optimize for any cost. Use this mode if you care about solve speed and don't have a preference on the solution.
  • optimize_distance: In this mode the solver will always run for a given period of time, in order to find better solutions, even if one was found already. The solver will prefer solutions closer to the seed (initial joint configuration) in joint-space. Use this mode if your application can afford spending additional time in IK in exchange for better solutions.
Make your example_robot_mock/config/moveit/pose_ik.yaml

We will use the optimize_distance setting.

manipulator:
kinematics_solver: pose_ik_plugin/PoseIKPlugin
target_tolerance: 0.001
solve_mode: "optimize_distance"
optimization_timeout: 0.005


moveit_params.joint_limits

Type: object (optional)

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

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

Our URDF can contain information such as joint position and velocity limits, but does not contain acceleration and jerk limits. For any joint we will use MoveIt to plan trajectories with, we must provide the acceleration limits. We do this in the moveit_params.joint_limits file where we can also override certain information provided in the URDF.

Make your example_robot_mock/config/moveit/joint_limits.yaml
# joint_limits.yaml allows overriding per-joint URDF values used for motion planning and speicyfing additional dynamic limits.
# - Positions limits can be overridden `has_position_limits`, `min_position` and `max_position`.
# - Velocity limits can be overridden with `has_velocity_limits` and `max_velocity`.
# - Acceleration limits can be set with `has_acceleration_limits` and `max_acceleration`.
# - Jerk limits can be set with `has_jerk_limits` and `max_jerk`.
joint_limits:
joint_1:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0
joint_2:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0
joint_3:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0
joint_4:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0
joint_5:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0
joint_6:
has_velocity_limits: true
max_velocity: 2.5
has_acceleration_limits: true
max_acceleration: 5.0

moveit_params.joint_jog

Type: object (optional)

Description: Configuration for Joint Jog teleoperation functionality.

moveit_params:
joint_jog:
package: "example_robot_mock"
path: "config/moveit/joint_jog.yaml"
Make your example_robot_mock/config/moveit/joint_jog.yaml
# 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']

moveit_params.pose_jog

Type: object (optional)

Description: Configuration for pose jogging functionality.

moveit_params:
pose_jog:
package: "example_robot_mock"
path: "config/moveit/pose_jog.yaml"
Make your example_robot_mock/config/moveit/pose_jog.yaml
# Planning groups to use in PoseJog, and their corresponding VFC controllers.
# The number of elements in `planning_groups` and `controllers` must match.
planning_groups: ['manipulator']
controllers: ['velocity_force_controller']


moveit_params.sensors_3d

Type: object (optional)

Description: Configuration for point cloud processing such as Octomap functionality.

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

Our example_robot_mock does not have simulated perception so we will not configure this for now.


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 will not control via the ROS 2 Control framework. For details, see the Guide to Non-ROS 2 Control Drivers.

moveit_params:
moveit_simple_controller_manager:
package: "another_robot_sim"
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

Multi-arm, Mobile Manipulator, and Multi-tip Tool Teleoperation Considerations

Using the settings icon you can switch between groups defined in your moveit_params.pose_jog file when using IMarker or Pose Jog. This is useful for when you want to control a specific arm or only the arm on a mobile manipulator.

The UI will report the currently selected group (for IMarker and Pose Jog), controller (for Pose Jog), and IMarker frame (for IMarker) in the {planning_groups}, {controllers}, and {tip_links} blackboard variables.

For a multi-arm configuration example, look at multi_arm_sim. For a mobile manipulator configuration example, look at hangar_sim.

warning

IMarker control currently does not support switching between tip links if a planning group has multiple tip links. If you have an end effector with multiple tip links you wish to control, you should create separate planning groups (with only a single tip link) for each.


step6 Checkpoint

Your example_robot_ws workspace should now look like branch step6.