Skip to content

Jerk-limited Type Trajectory for Multicopters

The Jerk-limited trajectory type provides smooth motion in response to user stick input or mission changes (e.g.: for filming, mapping, cargo). It generates symmetric smooth S-curves where the jerk and acceleration limits are always guaranteed.

This trajectory type is always enabled in Mission mode. To enable it in Position mode set the parameter: MPC_POS_MODE=3.

INFO

The jerk-limited type is not used by default in position mode. It may not be suitable for vehicles/use-cases that require a faster response - e.g. racer quads.

Trajectory Generator

The graph below shows a typical jerk-limited profile with the following constraints:

  • jMax: maximum jerk
  • a0: initial acceleration
  • aMax: maximum acceleration
  • a3: final acceleration (always 0)
  • v0: initial velocity
  • vRef: desired velocity

The constraints jMax, aMax are configurable by the user via parameters and can be different in manual position control and auto mode.

The resulting velocity profile is often called "S-Curve".

Jerk-limited trajectory

Manual Mode

In manual position mode, the sticks are mapped to velocity where a full XY-stick deflection corresponds to MPC_VEL_MANUAL and a full Z-stick deflection corresponds to MPC_Z_VEL_MAX_UP (upward motion) or MPC_Z_VEL_MAX_DN (downward motion).

Constraints

XY-plane:

Z-axis:

Auto Mode

In auto mode, the desired velocity is MPC_XY_CRUISE but this value is automatically adjusted depending on the distance to the next waypoint, the maximum possible velocity in the waypoint and the maximum desired acceleration and jerk. The vertical speed is defined by MPC_Z_V_AUTO_UP (upward motion) and MPC_Z_V_AUTO_DN (downward motion).

Constraints

XY-plane:

Z-axis:

Distance to velocity gains when close to a waypoint: