Skip to content

MoveIt 2

Practical

MoveIt 2 is the motion planning framework for ROS 2, providing manipulation capabilities including motion planning, kinematics, collision detection, and trajectory execution. It’s the third most popular package in the ROS ecosystem and is developed by PickNik Robotics.

Prerequisites

Why MoveIt 2 Matters

  • Motion planning: Automatically find collision-free paths for robot arms
  • Inverse kinematics: Multiple solver options (KDL, TRAC-IK, pick_ik)
  • Collision detection: Real-time checking against world and self-collision
  • Teleoperation: MoveIt Servo enables real-time joystick/VR control
  • Task composition: MoveIt Task Constructor for complex pick-and-place sequences

Architecture

┌─────────────────────────────────────────────────────────────────┐
│ User Application │
│ (Python API / C++ API / RViz) │
└────────────────────────────┬────────────────────────────────────┘
┌────────────────────────────▼────────────────────────────────────┐
│ move_group Node │
│ ┌──────────────┐ ┌──────────────┐ ┌──────────────┐ │
│ │ Planning │ │ Kinematics │ │ Collision │ │
│ │ Plugin │ │ Plugin │ │ Checker │ │
│ │ (OMPL/STOMP) │ │ (KDL/TRAC) │ │ (FCL) │ │
│ └──────────────┘ └──────────────┘ └──────────────┘ │
│ │ │
│ ┌──────────────────────────▼──────────────────────────────┐ │
│ │ Planning Scene Monitor │ │
│ │ (Robot State + World Geometry) │ │
│ └──────────────────────────────────────────────────────────┘ │
└────────────────────────────┬────────────────────────────────────┘
┌────────────────────────────▼────────────────────────────────────┐
│ ros2_control │
│ (Joint Trajectory Controller) │
└────────────────────────────┬────────────────────────────────────┘
┌────────▼────────┐
│ Robot / Sim │
└─────────────────┘

Planning Pipeline

Goal Pose → IK Solver → Joint Goal → Motion Planner → Trajectory → Controller
↓ ↓
Planning Scene ──────────── Collision Checking

Installation

Terminal window
# Jazzy (recommended LTS)
sudo apt install ros-jazzy-moveit
# Humble
sudo apt install ros-humble-moveit

Basic Motion Planning

import rclpy
from moveit.planning import MoveItPy
from geometry_msgs.msg import PoseStamped
def main():
rclpy.init()
# Initialize MoveItPy
moveit = MoveItPy(node_name="moveit_py")
arm = moveit.get_planning_component("arm")
# Set target pose
target_pose = PoseStamped()
target_pose.header.frame_id = "base_link"
target_pose.pose.position.x = 0.5
target_pose.pose.position.y = 0.0
target_pose.pose.position.z = 0.4
target_pose.pose.orientation.w = 1.0
arm.set_goal_state(
pose_stamped=target_pose,
pose_link="gripper_link"
)
# Plan and execute
plan_result = arm.plan()
if plan_result:
arm.execute()
if __name__ == "__main__":
main()

Motion Planners

MoveIt supports multiple planning backends via plugins:

PlannerLibraryUse Case
RRT, RRT*, PRMOMPLGeneral-purpose sampling-based
STOMPMoveItTrajectory optimization, smooth paths
PilzMoveItIndustrial linear/circular motions
cuMotionNVIDIA IsaacGPU-accelerated, cluttered environments

IK Solvers

SolverCharacteristics
KDLDefault, Newton-based, struggles near joint limits
TRAC-IKMore reliable near joint limits, combines KDL + SQP
pick_ikModern solver, gradient descent + evolutionary algorithms

MoveIt Servo (Real-time Control)

Stream velocity commands for teleoperation:

from geometry_msgs.msg import TwistStamped
# Publish Cartesian velocity commands
twist = TwistStamped()
twist.header.frame_id = "base_link"
twist.header.stamp = node.get_clock().now().to_msg()
twist.twist.linear.x = 0.1 # 10 cm/s forward
servo_publisher.publish(twist)

MoveIt Servo accepts:

  • geometry_msgs/TwistStamped — Cartesian velocities
  • control_msgs/JointJog — Joint velocities
  • geometry_msgs/PoseStamped — Pose targets

MoveIt Task Constructor

Framework for composing complex manipulation sequences:

┌─────────────────┐
│ Current State │ (Generator)
└────────┬────────┘
┌─────────────────┐
│ Move to Pre-grasp│ (Connector)
└────────┬────────┘
┌─────────────────┐
│ Close Gripper │ (Propagator)
└────────┬────────┘
┌─────────────────┐
│ Lift Object │ (Propagator)
└────────┬────────┘
┌─────────────────┐
│ Move to Place │ (Connector)
└────────┬────────┘
┌─────────────────┐
│ Open Gripper │ (Propagator)
└─────────────────┘

Configuration Files

MoveIt requires several configuration files, generated by the Setup Assistant:

FilePurpose
*.urdfRobot geometry (links, joints, meshes)
*.srdfPlanning groups, poses, collision pairs
kinematics.yamlIK solver configuration
ompl_planning.yamlOMPL planner parameters
joint_limits.yamlVelocity/acceleration limits
moveit_controllers.yamlros2_control integration

NVIDIA cuMotion Integration

GPU-accelerated motion planning via Isaac ROS:

Terminal window
# Install cuMotion MoveIt plugin
sudo apt install ros-humble-isaac-ros-cumotion-moveit

Key advantages:

  • Plans thousands of trajectories in parallel on GPU
  • Sub-second planning in cluttered environments
  • Smooth, time-optimal trajectories

Common Issues

ProblemCauseSolution
”No IK solution found”Target unreachable or in collisionCheck workspace limits, verify pose is reachable
”Planning failed”Obstacles blocking pathUpdate planning scene, try different planner
Jerky motionJoint limits too aggressiveTune joint_limits.yaml
Slow planningComplex environmentUse cuMotion or tune planner parameters

Learn More

Sources