Skip to content
alexanderdu15 edited this page Dec 17, 2024 · 11 revisions

MPCGPU is a GPU-accelerated trajectory optimization solver for real-time Nonlinear Model Predictive Control. It is deployed in Indy7 SDK through TrajoptNode, which is a ROS 2 node.

image

See here for mathematical background.

Key Features

  • Kilohertz control rates for trajectories up to 512 knot points
  • Exploits sparsity and natural parallelism in direct trajectory optimization
  • Efficiently handles larger optimization problems compared to CPU-based approaches
  • Custom GPU-optimized PCG solver that outperforms state of the art CPU-based methods

Trajopt Node

Communication Interface

  • Subscriptions:

    • Topic: joint_states
    • Message Type: indy7_msgs/msg/JointState
    • Purpose: Current robot state feedback
  • Publications:

    • Topic: joint_trajectory
    • Message Type: indy7_msgs/msg/JointTrajectory
    • Purpose: Optimized trajectory commands

Current Parameters

You can change these in trajopt_node.cu

Duration timestep_ = 0.01;  // 10ms timestep
float pcg_exit_tol_ = 5e-4; // PCG convergence tolerance
int pcg_max_iter_ = 173;    // Maximum PCG iterations

Other MPCGPU parameters can be changed in: external/MPCGPU/include/common/settings.cuh

Usage

Running the Node

# Launch with a reference trajectory file
ros2 run indy7_control trajopt_node /path/to/trajectory.csv

Reference Trajectory Format

  • CSV file containing end-effector positions
  • Each row represents a knot point
  • Columns: [x, y, z, r, p, y] positions and rotations

Clone this wiki locally