MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
MoveIt Pro Core Python Bindings

MoveIt Pro provides Python bindings to its core algorithms, including advanced inverse kinematics solvers, motion planners, and kinematic utilities. These bindings enable Python developers to leverage MoveIt Pro's high-performance C++ implementations directly from Python, making it easy to integrate sophisticated motion planning capabilities into Python applications and workflows.

This document introduces the MoveIt Pro Python bindings (moveit_pro_py) with practical examples and code snippets to help you get started quickly.

Overview

moveit_pro_py provides a Python interface to MoveIt Pro's advanced motion planning capabilities, including:

  • Inverse Kinematics (IK): Single pose and path IK with configurable solvers
  • Cartesian Planning: Path planning with Cartesian constraints
  • RRT Planning: ProRRT planner for collision-free joint-space trajectories
  • Jacobian Computation: Single and multi-tip Jacobians for velocity control
  • Planning Scene: Robot state and collision environment management
  • Trajectory Generation: Convert waypoints to executable trajectories

Quick Start

Setup your license key

Before using MoveIt Pro Python bindings, ensure that you have a valid license key set up. The license validation is handled automatically when you try to use any protected functionality. The license number should be set in the MOVEIT_LICENSE_KEY environment variable, e.g.:

export MOVEIT_LICENSE_KEY="YOUR_LICENSE_KEY"

Loading a Robot Model from Files

Load a robot model directly from URDF and SRDF files without ROS parameters (complete example):

import os
import rclpy
import rclcpp
from ament_index_python.packages import get_package_share_directory
from moveit_pro import RobotModel
# Initialize ROS contexts
rclpy.init()
rclcpp.init()
# Load robot description files
moveit_resources_dir = get_package_share_directory("moveit_resources_panda_description")
urdf_path = os.path.join(moveit_resources_dir, "urdf", "panda.urdf")
moveit_config_dir = get_package_share_directory("moveit_resources_panda_moveit_config")
srdf_path = os.path.join(moveit_config_dir, "config", "panda.srdf")
# Create robot model
model = RobotModel(urdf_path, srdf_path)
# Access joint model groups
group_name = "panda_arm"
joint_model_group = model.get_joint_model_group(group_name)
print(f"Active joints: {joint_model_group.active_joint_model_names}")

See examples/plan_joint_space.py in the installed moveit_pro_py package for a complete example.

Planning Scene Monitor with URDF/SRDF Strings

Create a Planning Scene Monitor without ROS parameters, using URDF/SRDF strings directly:

import rclpy
import rclcpp
from moveit_pro.planning import PlanningSceneMonitor, RobotModelLoaderOptions
# Initialize ROS contexts
rclpy.init()
rclcpp.init()
# Read URDF and SRDF content
with open(urdf_path, 'r') as f:
urdf_string = f.read()
with open(srdf_path, 'r') as f:
srdf_string = f.read()
# Create RobotModelLoaderOptions with strings
options = RobotModelLoaderOptions(urdf_string, srdf_string)
# Create planning scene monitor
node = rclcpp.Node("planning_node")
psm = PlanningSceneMonitor(node, options, "planning_scene_monitor")
psm.start_state_monitor()
# Access planning scene
with psm.read_only() as scene:
current_state = scene.current_state

See examples/start_psm.py in the installed moveit_pro_py package for a complete example.

Planning Scene Monitor with ROS Parameters

Traditional approach using ROS parameters:

import rclpy
import rclcpp
from rclpy.node import Node
from moveit_pro.planning import PlanningSceneMonitor
# Initialize ROS
rclpy.init()
rclcpp.init()
# Create planning scene monitor from ROS parameter
# Assumes that the `robot_description` parameter is set on the parameter server
node = Node("my_planning_node")
psm = PlanningSceneMonitor(
rclcpp.Node("cpp_node"),
"robot_description",
"planning_scene_monitor"
)
psm.start_state_monitor()
# Access planning scene
with psm.read_only() as scene:
# Work with planning scene
current_state = scene.current_state

Core Modules

The examples below include only code snippets and are not full examples. See the examples under moveit_pro_py/demo/ for complete scripts.

moveit_pro.kinematics

Inverse kinematics and kinematic queries.

Single Pose IK

Solve IK for a single end-effector pose:

import numpy as np
from moveit_pro import kinematics
# Create target pose (4x4 transformation matrix)
target_pose = np.eye(4)
target_pose[0:3, 3] = [0.5, 0.2, 0.3] # Translation
# Create pose target
target = kinematics.PoseTarget()
target.tip_link = robot_model.get_link_model("end_effector_link")
target.root_pose_tip = target_pose
# Get current joint values as seed
model_group = robot_model.get_joint_model_group("manipulator")
seed = state.get_joint_group_positions(model_group.name)
# Create validation function
def is_valid_solution(joint_values):
"""Check if solution is valid (e.g., collision-free)"""
return True
# Solve IK
solution = kinematics.solve_ik(
state,
model_group,
[target],
seed,
timeout=1.0,
validation_fn=is_valid_solution
)

IK with Custom Parameters

# Create custom IK parameters
params = kinematics.IKParams()
params.solve_mode = kinematics.IKSolveMode.OPTIMIZE_DISTANCE
params.target_tolerance = 0.01
params.gd_max_iters = 100
params.gd_jacobian_damping = 0.001
# Solve with custom parameters
solution = kinematics.solve_ik(
state,
model_group,
[target],
seed,
timeout=1.0,
validation_fn=is_valid_solution,
params=params
)

Multi-Target IK

Solve IK for multiple end effectors simultaneously:

# Create multiple targets
target1 = kinematics.PoseTarget()
target1.tip_link = robot_model.get_link_model("left_gripper")
target1.root_pose_tip = left_target_pose
target2 = kinematics.PoseTarget()
target2.tip_link = robot_model.get_link_model("right_gripper")
target2.root_pose_tip = right_target_pose
# Solve for both simultaneously
solution = kinematics.solve_ik(
state,
model_group,
[target1, target2],
seed,
timeout=1.0,
validation_fn=is_valid_solution
)

moveit_pro.kinematics.cartesian

Cartesian path planning and Jacobian computation.

Cartesian Path IK

Compute joint-space path that follows a Cartesian trajectory:

from moveit_pro.kinematics import cartesian
import numpy as np
# Define Cartesian path (list of 4x4 poses)
start_pose = state.get_global_link_transform("end_effector_link")
end_pose = start_pose.copy()
end_pose[0, 3] += 0.3 # Move 30cm in X
cartesian_path = [start_pose, end_pose]
# Compute joint waypoints
try:
joint_waypoints = cartesian.path_ik(
state,
model_group,
["end_effector_link"],
cartesian_path
)
except cartesian.PartialPathError as e:
# Handle partial solutions
print(f"Only found partial path: {len(e.partial_path)} waypoints")
joint_waypoints = e.partial_path

Path IK with Options

# Configure path IK options
options = cartesian.PathIKOptions()
options.set_blending_radius(0.05) # Smooth path
options.set_tip_constraint(
cartesian.PathIKOptions.TipConstraint.POSITION_ONLY
)
options.set_max_optimizer_iterations(10)
options.set_joint_limit_avoidance_parameters(0.1, 0.2)
# Add tip offset (e.g., for tool center point)
tip_offset = np.eye(4)
tip_offset[0:3, 3] = [0.0, 0.0, 0.15] # 15cm offset in Z
options.set_tip_offset(tip_offset)
# Compute path with options
joint_waypoints = cartesian.path_ik(
state,
model_group,
["end_effector_link"],
cartesian_path,
options
)

Multi-Tip Cartesian Planning

Plan coordinated motion for multiple end effectors:

# Define paths for both grippers
left_path = [left_start, left_end]
right_path = [right_start, right_end]
# Interleave waypoints: [left1, right1, left2, right2, ...]
combined_path = []
for left, right in zip(left_path, right_path):
combined_path.extend([left, right])
# Plan with multiple tips
joint_waypoints = cartesian.path_ik(
state,
model_group,
["left_gripper", "right_gripper"],
combined_path,
options
)

Jacobian Computation

Compute Jacobian for velocity control:

# Single tip Jacobian
jacobian = cartesian.compute_jacobian_for_chain(
state,
"manipulator",
"end_effector_link",
tip_offset=np.zeros(3)
)
# Returns 6 x n_joints matrix
# Multi-tip Jacobian
jacobian = cartesian.compute_multi_tip_jacobian(
state,
"manipulator",
["left_gripper", "right_gripper"],
[np.zeros(3), np.zeros(3)]
)
# Returns (6 * n_tips) x n_joints matrix

Velocity Inverse Kinematics

Convert Cartesian velocities to joint velocities:

# Compute Jacobian
J = cartesian.compute_jacobian_for_chain(
state, "manipulator", "end_effector_link", np.zeros(3)
)
# Desired Cartesian velocity [vx, vy, vz, wx, wy, wz]
cartesian_vel = np.array([0.1, 0.0, 0.0, 0.0, 0.0, 0.0])
# Compute joint velocities
joint_vel = cartesian.velocity_inverse_kinematics(
J,
damping=0.01,
cartesian_velocity=cartesian_vel,
nullspace_velocity=np.zeros(n_joints)
)

moveit_pro.planning

Motion planning and trajectory generation.

Planning Scene

Access robot state and collision environment:

from moveit_pro.planning import PlanningScene, PlanningSceneMonitor
# Read-only access (concurrent safe)
with psm.read_only() as scene:
# Get robot state
current_state = scene.current_state
current_joints = current_state.get_joint_group_positions("manipulator")
# Get link transforms
ee_pose = current_state.get_global_link_transform("end_effector_link")
# Access robot model
robot_model = scene.robot_model
model_group = robot_model.get_joint_model_group("manipulator")
# Set kinematic limits
robot_model.set_group_velocity_bounds("manipulator", [-1.0]*7, [1.0]*7)
robot_model.set_group_acceleration_bounds("manipulator", [-2.0]*7, [2.0]*7)
# Write access (for modifications)
with psm.read_write() as scene:
# Modify robot state
scene.current_state.set_joint_group_positions("manipulator", new_positions)
scene.current_state.update()
# Add collision objects, modify scene, etc.

ProRRT Planner

Plan collision-free trajectories in joint space:

from moveit_pro.planning import pro_rrt
from trajectory_msgs.msg import JointTrajectory
# Get start and goal configurations
start = scene.current_state.get_joint_group_positions("manipulator")
goal = np.array([0.0, -1.57, 1.57, 0.0, 1.57, 0.0, 0.0])
# Plan trajectory
trajectory = pro_rrt.plan_trajectory_to_joint_goal(
"manipulator",
start,
goal,
scene
)
# Returns trajectory_msgs/JointTrajectory

ProRRT with Custom Parameters

# Configure RRT parameters
rrt_params = pro_rrt.RRTParams()
rrt_params.max_iterations = 10000
rrt_params.configuration_space_step = 0.05
rrt_params.timeout_s = 5.0
rrt_params.seed = 42
# Configure trajectory parameters
traj_params = pro_rrt.TrajectoryParams()
traj_params.velocity_scale_factor = 0.5
traj_params.acceleration_scale_factor = 0.5
traj_params.sampling_rate = 100 # Hz
# Plan with custom parameters
trajectory = pro_rrt.plan_trajectory_to_joint_goal(
"manipulator",
start,
goal,
scene,
rrt_params=rrt_params,
trajectory_params=traj_params
)
Configuration parameters for the RRT planner.
Definition planners/pro_rrt/include/pro_rrt/pro_rrt.hpp:25
Parameters for the trajectory generation.
Definition planners/pro_rrt/include/pro_rrt/pro_rrt.hpp:43

ProRRT with Constraints

# Add path constraints
constraints = pro_rrt.Constraints()
# Configure constraints (specific API depends on implementation)
trajectory = pro_rrt.plan_trajectory_to_joint_goal(
"manipulator",
start,
goal,
scene,
constraints_list=[constraints]
)
Definition of kinematic constraints to take into account during planning.
Definition planners/pro_rrt/include/pro_rrt/pro_rrt.hpp:87

Create Trajectory from Waypoints

Convert joint-space waypoints to a time-parameterized trajectory:

from moveit_pro.planning import create_trajectory_message_from_waypoints
# Waypoints from cartesian path IK
joint_waypoints = [
np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]),
np.array([0.5, -0.5, 0.5, -0.5, 0.5, -0.5, 0.0]),
np.array([1.0, -1.0, 1.0, -1.0, 1.0, -1.0, 0.0]),
]
# Create trajectory
trajectory = create_trajectory_message_from_waypoints(
model_group,
joint_waypoints,
velocity_scale_factor=1.0,
acceleration_scale_factor=1.0,
sampling_rate=100 # Hz
)

Complete Examples

Full example scripts are available in the examples/ directory of the installed moveit_pro_py package (typically located at <install_prefix>/share/moveit_pro_py/examples/):

Error Handling

from moveit_pro import MessageError
from moveit_pro.kinematics.cartesian import PartialPathError
from moveit_pro.planning.pro_rrt import PlanningErrorException
# IK failures
try:
solution = kinematics.solve_ik(...)
except MessageError as e:
print(f"IK failed: {e}")
# Partial cartesian paths
try:
waypoints = cartesian.path_ik(...)
except PartialPathError as e:
print(f"Partial path found: {len(e.partial_path)} waypoints")
waypoints = e.partial_path # Use partial solution
# Planning failures
try:
trajectory = pro_rrt.plan_trajectory_to_joint_goal(...)
except PlanningErrorException as e:
print(f"Planning failed: {e}")
except ValueError as e:
print(f"Invalid input: {e}")

API Reference

Classes

  • kinematics.PoseTarget: Target pose for IK solver
  • kinematics.IKParams: Parameters for IK solver
  • kinematics.IKSolveMode: Enum for IK solving strategies
  • cartesian.PathIKOptions: Options for Cartesian path IK
  • cartesian.PathIKOptions.TipConstraint: Enum for constraint types
  • cartesian.PartialPathError: Exception with partial path data
  • pro_rrt.RRTParams: Parameters for RRT planner
  • pro_rrt.TrajectoryParams: Parameters for trajectory generation
  • pro_rrt.Constraints: Path constraints for planning
  • pro_rrt.PlanningErrorException: Planning failure exception
  • PlanningScene: Robot state and collision environment
  • PlanningSceneMonitor: Thread-safe planning scene access

Functions

Kinematics

  • kinematics.solve_ik(): Solve inverse kinematics
  • cartesian.path_ik(): Cartesian path inverse kinematics
  • cartesian.compute_jacobian_for_chain(): Single-tip Jacobian
  • cartesian.compute_multi_tip_jacobian(): Multi-tip Jacobian
  • cartesian.velocity_inverse_kinematics(): Velocity IK

Planning

  • pro_rrt.plan_trajectory_to_joint_goal(): Plan joint-space trajectory
  • create_trajectory_message_from_waypoints(): Create trajectory message

Best Practices

  1. Always initialize both rclpy and rclcpp: Required for proper ROS communication
  2. Use context managers with PlanningSceneMonitor: Ensures thread-safe access
  3. Update robot state before queries: Call state.update() after modifications
  4. Provide validation functions: Prevent invalid IK solutions (collisions, limits)
  5. Handle partial paths gracefully: Cartesian planning may find partial solutions
  6. Set reasonable timeouts: Prevent indefinite waiting in IK/planning
  7. Configure kinematic limits: Set velocity/acceleration bounds before planning
  8. Use appropriate scaling factors: Control speed of generated trajectories

Troubleshooting

Problem: IK always fails

  • Check that target pose is reachable
  • Increase timeout
  • Verify robot state is updated
  • Ensure validation function isn't too restrictive

Problem: Cartesian path fails

  • Try smaller steps between waypoints
  • Adjust path IK options (blending, constraints)
  • Use position-only constraints for more flexibility
  • Check joint limits and singularities

Problem: Planning fails with collisions

  • Verify collision objects in planning scene
  • Check self-collision settings
  • Increase configuration space step for RRT
  • Add clearance to obstacles

Problem: State updates don't reflect

  • Must call state.update() after modifications
  • Ensure using read_write context for modifications
  • Check that monitor is receiving state updates

License

Copyright 2025 PickNik Inc. All rights reserved. Proprietary and confidential.