Prerequisites

This guide targets Ubuntu 22.04 LTS with ROS2 Humble Hawksbill (EOL May 2027), Python 3.10, and the MoveIt2 binary release for Humble. Install the full desktop stack before proceeding:

  • ROS2 Humble desktop-full: sudo apt install ros-humble-desktop-full — includes rviz2, rqt, and all core libraries.
  • MoveIt2: sudo apt install ros-humble-moveit — pulls in moveit_core, moveit_ros_planning, moveit_ros_move_group, and all planner plugins.
  • ros2_control: sudo apt install ros-humble-ros2-control ros-humble-ros2-controllers — mandatory for hardware abstraction.
  • Python packages: pip install transforms3d numpy scipy for kinematic utilities used in the tutorial snippets.
  • colcon: sudo apt install python3-colcon-common-extensions for building your custom packages.

Verify your environment: ros2 doctor --report should show no errors. If you see "network configuration" warnings on a single machine, export ROS_LOCALHOST_ONLY=1 to prevent multicast issues.

URDF Setup

The Unified Robot Description Format (URDF) is the single source of truth for your arm's kinematics, dynamics, and hardware interface. A well-authored URDF prevents the majority of planning failures.

Joint limits are the first thing to get right. Soft limits (used by MoveIt2 for planning) should be 5° inside the hard limits (used by the firmware for emergency stop). If your arm's J2 hardware limit is −120° to +120°, set the URDF lower="-2.0944" and upper="2.0944" (±120° in radians), then set MoveIt2 joint limits to ±117° in joint_limits.yaml.

Inertia tensors are commonly wrong and cause unstable simulation dynamics. For a link of mass m approximated as a cylinder of radius r and length L, use ixx = m*(3r²+L²)/12, iyy = ixx, izz = m*r²/2. Off-diagonal terms are zero for symmetric links. Wrong inertia (e.g., all-zero or placeholder values) will cause Gazebo physics to explode and can make MoveIt2's collision checker behave unpredictably.

Visual vs. collision geometry: Use high-poly meshes (DAE/OBJ) for visual tags and simplified convex hull meshes for collision tags. MoveIt2's FCL collision checker runs at planning time against the collision geometry — over-detailed meshes increase planning time 5–10×. Generate convex hulls with python3 -c "import trimesh; m = trimesh.load('link.dae'); m.convex_hull.export('link_collision.stl')".

The ros2_control hardware interface tag must appear inside your URDF's <robot> element. This tag declares the control interface type and plugin class for your hardware driver:

  • hardware plugin: Set to your driver, e.g. openarm_hardware/OpenArmSystemHardware for OpenArm arms.
  • command interface: Declare position for position control. Also declare velocity and effort if your driver supports them.
  • state interface: Always declare position and velocity. Add effort if the hardware provides torque feedback.
  • param tag: Pass hardware-specific parameters (e.g. serial port, baud rate, robot IP) through param tags inside the hardware element.

MoveIt2 Core Concepts

Understanding these four concepts before writing a single line of planning code will save hours of debugging.

MoveGroup is the high-level planning interface. It wraps the planning pipeline, the planning scene, and the execution manager. You interact with it via the MoveGroupInterface C++ class or the moveit_commander Python wrapper. A MoveGroup is defined for a named group in your SRDF (e.g. "arm", "gripper") and acts as the entry point for all planning requests.

Planning pipeline chains a planner plugin with optional pre/post-processing adapters. MoveIt2 ships three planner backends — choose based on your task:

PlannerBest ForLimitations
OMPL (default)General-purpose, cluttered environments, no dynamics neededNon-deterministic; replanning may give different paths
CHOMPSmooth, gradient-optimized trajectoriesCan get stuck in local minima; slow in tight spaces
PILZ Industrial Motion PlannerDeterministic LIN/PTP/CIRC industrial movesNo obstacle avoidance; requires clear workspace

Planning scene is a live 3D representation of the environment. It starts from your URDF and is updated at runtime with collision objects (boxes, spheres, meshes) added via the PlanningSceneInterface. Always add your table, fixture, and known obstacles to the scene before planning — MoveIt2 plans through free space, not around unknown objects.

Constraint planning: MoveIt2 supports path constraints (e.g., keep end-effector upright throughout motion), joint constraints, position constraints, and orientation constraints. Constraints are specified in the MotionPlanRequest. OMPL's constraint-aware planning requires the ompl_constraint_planning plugin. For simple orientation maintenance (e.g., keep gripper level while moving), an orientation constraint with tolerance ±10° around the pitch and roll axes works reliably.

Motion Planning Tutorial

This four-step workflow takes you from a fresh terminal to executing a collision-checked Cartesian path.

Step 1 — Launch the demo: ros2 launch moveit2_tutorials demo.launch.py brings up rviz2 with the Panda demo arm. Swap the launch file for your own arm's MoveIt2 configuration package (generated by the MoveIt2 Setup Assistant).

Step 2 — Set planning scene: Publish a CollisionObject message on /planning_scene. Add a box representing your work table at the correct pose. Confirm it appears in rviz2's "Planning Scene" display before continuing.

Step 3 — Plan a Cartesian path: Use computeCartesianPath(waypoints, eef_step=0.01, jump_threshold=0.0) where eef_step=0.01 means one waypoint per centimeter of end-effector travel. A return value of 1.0 means 100% of the path was computed. Values below 0.9 typically mean a joint limit or collision was hit mid-path — adjust your waypoints or relax the constraint.

Step 4 — Execute with collision check: Call execute(plan) which passes the trajectory through the trajectory execution manager. The manager streams joint commands to ros2_control at the configured frequency (typically 250–500 Hz). If a collision is detected during execution by the monitored planning scene (requires the is_diff=True scene update stream), MoveIt2 will abort the trajectory.

Teleoperation Servo Mode

moveit_servo enables real-time Cartesian velocity control without replanning. It accepts TwistStamped messages at up to 100 Hz and continuously generates joint velocity commands that track the requested end-effector velocity, subject to joint limits and singularity avoidance.

To launch servo mode for your arm, add the servo node to your launch file with the servo configuration YAML. Key parameters:

  • move_group_name: The planning group to servo — must match your SRDF group name.
  • cartesian_command_in_topic: Default /servo_node/delta_twist_cmds. Publish TwistStamped here at 50–100 Hz.
  • joint_command_out_topic: Output JointTrajectory forwarded to ros2_control.
  • incoming_command_timeout: Set to 0.1s. If no command is received within this window, servo stops the arm — a critical safety feature for teleop.
  • lower_singularity_threshold / hard_stop_singularity_threshold: Set to 17 and 30 (condition number thresholds). The arm will slow down then stop as it approaches singularity.

For teleoperation data collection, publish twist commands derived from your input device (VR controller, SpaceMouse, or glove) at a consistent 100 Hz. Jitter in command frequency causes velocity discontinuities that degrade demonstration quality.

Common Issues and Fixes

  • Controller timing / "Trajectory point is not strictly increasing": Ensure your hardware interface implements HW_IF_POSITION (not HW_IF_VELOCITY) for position-controlled arms. Velocity interfaces require precise timing that USB-based arms cannot guarantee.
  • Joint limit violations during planning: Apply a 5° (0.0873 rad) safety margin in joint_limits.yaml by setting max_position and min_position inside the hard limits. This prevents the planner from generating trajectories that trigger the hardware's limit switches mid-execution.
  • Unstable dynamics in simulation: Wrong URDF inertia values are the most common cause. Verify each link's inertia with ros2 run robot_state_publisher robot_state_publisher --ros-args -p robot_description:="$(xacro my_robot.urdf.xacro)" and inspect inertia in the rqt robot description viewer.
  • MoveGroup fails to connect: Check that the move_group node is running (ros2 node list | grep move_group) and that your RMW (default Cyclone DDS) has the same domain ID as your other nodes. Set ROS_DOMAIN_ID=0 consistently.
  • Servo produces jerky motion: Ensure your servo command loop runs at a fixed rate. Use a ROS2 timer with create_timer(0.01, callback) rather than a while loop with sleep().

Key Packages Reference

PackagePurposeInstall
moveit_servoReal-time Cartesian servo / teleopIncluded in ros-humble-moveit
moveit_planners_omplOMPL sampling-based plannersIncluded in ros-humble-moveit
moveit_visual_toolsrviz2 debugging markers and trajectory visualizationros-humble-moveit-visual-tools
joint_state_broadcasterBroadcasts /joint_states from ros2_controlros-humble-ros2-controllers
robot_state_publisherPublishes TF tree from URDF + joint statesros-humble-robot-state-publisher
moveit_ros_perceptionOctoMap integration for 3D obstacle avoidanceIncluded in ros-humble-moveit