Trajectory generation for arms
A planned path is geometry. A trajectory is geometry plus timing. Time-optimal vs jerk-limited, trapezoidal vs S-curve, and the practical patterns for safe motion near humans.
A motion planner gives you a sequence of joint configurations. A trajectory adds when — velocities, accelerations, jerks. Get this layer right and the arm moves smoothly, hits its limits, and doesn't shake the operator. Get it wrong and you have collision-free chatter.
Path vs trajectory
- Path: an ordered sequence of waypoints. Just geometry.
- Trajectory: each waypoint annotated with time, velocity, and acceleration. Time-aware.
Most planners (MoveIt, OMPL) output a path. A separate stage — time parameterization — turns it into a trajectory honoring joint velocity, acceleration, and jerk limits.
The four common time-parameterization methods
1. Trapezoidal velocity profile
The classical default. Each segment between waypoints uses a velocity profile that:
- Accelerates at constant
a_maxuntil reachingv_max. - Cruises at
v_max. - Decelerates at constant
a_maxto zero.
Velocity over time looks like a trapezoid (or triangle if the segment is too short to reach v_max). Acceleration is piecewise constant — discontinuous at the corners. That's the problem: discontinuous acceleration → infinite jerk → mechanical resonance.
2. S-curve (jerk-limited)
Smooth out the acceleration ramps. Acceleration ramps up linearly to a_max, holds, ramps back to zero. The result is a 7-segment profile (jerk: +, 0, –, 0, –, 0, +) and continuous acceleration.
Tradeoff: smoother motion, slightly slower (because jerk-limited segments add ramp-up/ramp-down time).
S-curve is the production default for arms operating near humans (cobots, surgical robots) and for heavy industrial arms with mechanical resonances.
3. Time-optimal path parameterization (TOPP / TOPP-RA)
Given the path geometry and per-joint velocity/acceleration limits, find the timing that minimizes total execution time while respecting limits at every point. Solves a 1D dynamics problem along the path.
TOPP-RA (Reachability Analysis) is the modern variant. Available in toppra. Used by drone-racing teams and aggressive industrial setups.
Strengths: provably fastest given the constraints. Weaknesses: requires accurate joint limits; doesn't naturally include jerk limits (but extensions exist).
4. Polynomial / spline interpolation
Fit a high-order polynomial (often quintic or septic) through the waypoints. Continuity in higher derivatives by construction. Good for short, smooth motions; less good for long paths with many waypoints (oscillations).
For quadrotors and aggressive trajectories, minimum-snap polynomials (Mellinger 2011) are the standard.
Joint-space vs Cartesian-space
Two layers, both need timing:
- Joint-space trajectory: the path is in joint angles; time-parameterize per-joint velocity/acceleration. The natural output of motion planners.
- Cartesian-space trajectory: the path is in end-effector pose; time-parameterize linear and angular velocity at the gripper. The natural input for tasks like "draw a line, decelerate near the end."
For pick-and-place, both come up: free motion = joint-space; approach/lift = Cartesian-space.
The limits that matter
| Quantity | Why it matters | Typical limit |
|---|---|---|
| Joint position | Mechanical hard stops | From URDF |
| Joint velocity | Motor / driver / human safety | Half of motor max for cobots |
| Joint acceleration | Motor torque / inertia | Set per-arm; tune by experiment |
| Joint jerk | Mechanical resonance, smoothness | Empirical (5–50 m/s³ at end-effector) |
| Cartesian speed | Human safety standards (ISO 10218) | ≤ 250 mm/s near humans |
Safe-stop trajectory
Every production arm has a "safe stop" trajectory the controller falls back to: from the current state, decelerate at max acceleration to zero velocity, ending at the closest reachable position. Computed continuously; triggered on emergency.
The math: given current (\mathbf{q}, \dot{\mathbf{q}}) and \mathbf{a}_{\max}, time to stop is ||\dot{\mathbf{q}}|| / a_{\max}; stopping distance is ||\dot{\mathbf{q}}||^2 / (2 a_{\max}). Use this to determine maximum allowed velocity given a known minimum stopping distance.
For a cobot in a workcell with humans 30 cm away, max velocity is bounded so the arm can stop within 10 cm. ISO 10218-1 formalizes this.
Implementation in MoveIt 2
MoveIt provides three time-parameterization plugins:
- IterativeParabolicTimeParameterization: legacy default; fast, can produce overshoots near limits.
- IterativeSplineParameterization: uses spline fitting; smoother. Default for many configs.
- RuckigTrajectorySmoothing: Ruckig-based, jerk-limited. Production-grade. Ruckig is the open-source library.
Switch with controller.yaml:
move_group:
trajectory_execution:
allowed_execution_duration_scaling: 1.2
iterative_parabolic_time_parameterization:
max_velocity_scaling_factor: 0.5
max_acceleration_scaling_factor: 0.3
Most teams set scaling to 0.3–0.7 of the URDF limits. The URDF limits are often the absolute hardware max; running at half is safer and reduces wear.
Online trajectory adjustment
Sometimes the trajectory must change mid-execution: a person enters the workspace, a sensor detects an unexpected force, the goal moves. Two patterns:
- Stop and replan: halt the current trajectory; plan a new one from the current state. Latency ~50–500 ms.
- Online trajectory generation (OTG): a Ruckig-style smooth blend from current state to a new goal at every control tick. Latency ~1 ms; output always feasible.
OTG is the gold standard for reactive arms. Combine with MoveIt for global plans + OTG for local adjustments.
Common gotchas
- Joint limits respected by planner but not the time parameterization: the planner produces a path within joint limits; the parameterization scales velocities per joint, but tight limits on one joint force the whole trajectory to slow down. Watch for this.
- Discontinuous orientation: parameterizing in Cartesian with quaternion targets — without slerp, the rotation can take the long way around. Use slerp explicitly.
- Underestimated cycle time: a "5-second pick-and-place" with all the trajectory smoothing is often 8 seconds. Measure on hardware before promising cycle times.
- Wrist singularity at the goal: the path ends in a singular configuration; trajectory parameterization fights it. Add a final orientation tolerance.
Exercise
For a 6-DOF arm, plan a path between two poses. Time-parameterize it three ways: trapezoidal, S-curve (Ruckig), TOPP-RA. Compare execution time and the velocity/acceleration profiles. The trapezoidal version is the fastest in time but worst in jerk; TOPP-RA is the fastest while honoring acceleration limits; Ruckig is the smoothest. Production: pick TOPP-RA when speed matters, Ruckig when humans are near.
Next
Impedance control for assembly — the controller layer that lets the arm feel its way through peg-in-hole tasks instead of crushing them.
Comments
Sign in to post a comment.