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.
The jerk-limited type is 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 jerka0
: initial accelerationaMax
: maximum accelerationa3
: final acceleration (always 0)v0
: initial velocityvRef
: 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".
Manual Mode
In manual position mode, the sticks are mapped to velocity where a full stick deflection corresponds to MPC_VEL_MANUAL.
Constraints
XY-plane:
jMax
: MPC_JERK_MAXaMax
: MPC_ACC_HOR_MAX
Z-axis:
jMax
: MPC_JERK_MAXaMax
(upward motion): MPC_ACC_UP_MAXaMax
(downward motion): MPC_ACC_DOWN_MAX
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.
Constraints
XY-plane:
jMax
: MPC_JERK_AUTOaMax
: MPC_ACC_HOR
Z-axis:
jMax
: MPC_JERK_AUTOaMax
(upward motion): MPC_ACC_UP_MAXaMax
(downward motion): MPC_ACC_DOWN_MAX
Distance to velocity gains when close to a waypoint: