Position Slow Mode (Multicopter)
PX4 v1.15
Position Slow mode is a velocity and yaw rate limited version of the regular Position mode.
The mode works in exactly the same way as Position mode but with the controller stick deflection re-scaled to lower maximum velocities (and proportionally lower acceleration). You can use it to quickly slow down the vehicle to a safe speed (if it is moving faster than the maximum velocity in the limited axis). You can also use it to get more precision from stick input, in particular when flying close to obstacles, or to comply with regulations such as EASA's low-speed mode/function.
The velocity limits can be set using parameters, from an RC Controller rotary knob, slider, or switch, or using MAVLink. Limits set using an RC controller override those set by MAVLink, which in turn override those set using parameters. The limits can only be reduced below those for normal Position mode.
Set Limits using Parameters
The maximum values for slow mode horizontal velocity, vertical velocity, and yaw rate can be set using parameters. This approach is useful when the maximum desired speed in slow mode is fixed, and you just want to be able to quickly drop to a safer speed range (perhaps using a switch on your controller).
The table below shows the parameters used to set the maximum values for Position slow mode and Position mode, respectively, along with their default values.
Axis | Position slow mode | Position mode |
---|---|---|
Horizontal velocity | MC_SLOW_DEF_HVEL (3 m/s) | MPC_VEL_MANUAL (10 m/s) |
Vertical velocity | MC_SLOW_DEF_VVEL (1 m/s) | MPC_Z_VEL_MAX_UP (3 m/s) / MPC_Z_VEL_MAX_DN (1.5 m/s) |
Yaw rate | MC_SLOW_DEF_YAWR (45 °/s) | MPC_MAN_Y_MAX (150 °/s) |
From this you can see, for example, that when switching from Position mode to Position slow mode, the default maximum upward horizontal velocity is reduced from 10 m/s to 3 m/s. If traveling faster than 3 m/s horizontally you'd be slowed to 3 m/s.
Note that the parameters are used only if limits are not provided by from RC or MAVLink.
Set Limits using RC Control
You can map a rotary knob, slider, or switch, on a RC Controller to set the maximum velocity of an axis (horizontal/vertical/yaw). This approach is useful when the appropriate slow-mode maximum values can vary while flying.
If the input control is set to its highest value the vehicle will go as fast as in Position mode. If the input is set to its lowest value, the vehicle maximum velocity is set to the value in the corresponding MC_SLOW_MIN_
parameter (shown in the table below). If an RC control input is mapped for an axis it has priority over all other inputs.
The table below lists each axis along with the parameter used to select which RC AUX channel corresponds to the control knob, and the parameter that sets the lowest possible "maximum value" for the axis.
Axis | Parameter to map auxiliary input | Parameter for minimum value of maximum velocity |
---|---|---|
Horizontal velocity | MC_SLOW_MAP_HVEL | MC_SLOW_MIN_HVEL |
Vertical velocity | MC_SLOW_MAP_VVEL | MC_SLOW_MIN_VVEL |
Yaw rate | MC_SLOW_MAP_YAWR | MC_SLOW_MIN_YAWR |
To use this approach:
- Make sure you have a remote with an extra input and an extra RC channel to transmit it's position.
- Map the channel which contains the knobs position as one of the 6 auxiliary passthrough inputs by setting RC_MAP_AUXn to the corresponding RC channel number.
- Map that auxiliary input using the appropriate
MC_SLOW_MAP_
parameter for the axis you want it to control (see table above).
For example, if you want to map RC channel 8
to limit the horizontal velocity you could set RC_MAP_AUX1 to the value 8
and MC_SLOW_MAP_HVEL to the value 1
. The RC input from channel 8 then sets a horizontal velocity limit between MC_SLOW_MIN_HVEL and MPC_VEL_MANUAL.
Set Limits using MAVLink
You can adjust the velocity limits using the MAVLink message SET_VELOCITY_LIMITS. This approach is used primarily by automatic systems, for example to slow a vehicle when zooming a camera.
The message can set the maximum value on any of the axes by supplying a non-NAN
limit value. This overrides limit values set in parameters, but is ignored if the axis is mapped to an RC knob. The value can be updated from a message at any time, and is latched until either the next message or a mode switch.
Note that PX4 does not provide velocity limit telemetry (i.e. it does not support streaming the VELOCITY_LIMITS message).