Skip to content

Drive Modes (Ackermann Rover)

Flight modes (or more accurately "Drive modes" for ground vehicles) provide autopilot support to make it easier to manually drive the vehicle or to execute autonomous missions.

This section outlines all supported drive modes for Ackermann rovers.

For information on mapping RC control switches to specific modes see: Basic Configuration > Flight Modes.

WARNING

Selecting any other mode than those listed below will either stop the rover or can lead to undefined behaviour.

Manual Modes

Manual modes require stick inputs from the user to drive the vehicle.

Manual Controls

The sticks provide the same "high level" control effects over direction and rate of movement in all manual modes:

  • Left stick up/down: Drive the rover forwards/backwards (controlling speed)
  • Right stick left/right: Make a left/right turn (controlling steering angle (Manual mode) or yaw rate (Acro and Position)).

The manual modes provide progressively increasing levels of autopilot support for maintaining a course, speed, and rate of turn, compensating for external factors such as slopes or uneven terrain.

ModeFeatures
ManualNo autopilot support. User is responsible for keeping the rover on the desired course and maintaining speed and rate of turn.
Acro+ Maintains the yaw rate (This makes it feel more like driving a car than manual mode).
+ Allows maximum yaw rate to be limited (Protects against roll over).
Position+ Maintains the course (Best mode for driving a straight line).
+ Maintains speed against disturbances, e.g. when driving up a hill.
+ Allows maximum speed to be limited.
Overview mode mapping to control effect
ModeForward/backwards speedSteering angle/yaw rateRequired measurements
ManualDirectly map stick input to motor command.Directly map stick input to steering angle.None.
AcroDirectly map stick input to motor command.Stick input creates a yaw rate setpoint for the control system to regulate.yaw rate.
PositionStick input creates a speed setpoint for the control system to regulate.Stick input creates a yaw rate setpoint for the control system to regulate. If this setpoint is zero (stick is centered) the control system will keep the rover driving in a straight line.yaw rate, yaw, speed and global position (GPS).

Manual Mode

In this mode the stick inputs are directly mapped to motor commands. The rover does not attempt to maintain a specific orientation or compensate for external factors like slopes or uneven terrain! The user is responsible for making the necessary adjustments to the stick inputs to keep the rover on the desired course.

StickEffect
Left stick up/downDrive the rover forwards/backwards.
Right stick left/rightMove the steering angle to the left/right.

For the configuration/tuning of this mode see Manual mode.

Acro Mode

INFO

This mode requires a yaw rate measurement.

In this mode the vehicle regulates its yaw rate to a setpoint (but does not stabilize heading or regulate speed).

Yaw rate can be directly mapped to a steering input based on the forward speed of the rover:

δ=arctan(wbψ˙v)

with

  • wb: Wheel base,
  • δ: Steering angle,
  • ψ˙: Yaw rate
  • v: Forward speed.

For driving this means that the same right hand stick input will cause a different steering angle based on how fast you are driving. By limiting the maximum yaw rate, we can restrict the steering angle based on the speed, which can prevent the rover from rolling over. This mode will feel more like "driving a car" than Manual mode.

INFO

The yaw rate is only close loop controlled when driving forwards. When driving backwards the yaw rate setpoint is directly mapped to a steering angle using the equation above. This is due to the fact that rear wheel steering (driving a car with front-wheel steering backwards) is non-minimum-phase w.r.t to the yaw rate which leads to instabilities when doing closed loop control.

StickEffect
Left stick up/downDrive the rover forwards/backwards.
Right stick left/rightCreate a yaw rate setpoint for the control system to regulate. If this input is zero the control system will attempt to maintain a zero yaw rate (minimal disturbance rejection)

For the configuration/tuning of this mode see Acro mode.

Stabilized Mode

INFO

This mode requires a yaw rate and yaw estimate.

In this mode the vehicle regulates its yaw rate to a setpoint and will maintain its heading if this setpoint is zero (but does not regulate speed). Compared to Acro mode, this mode is much better at driving in a straight line as it can more effectively reject disturbances.

StickEffect
Left stick up/downDrive the rover forwards/backwards.
Right stick left/rightCreate a yaw rate setpoint for the control system to regulate. If this input is zero the control system will maintain the current yaw.

For the configuration/tuning of this mode see Stabilized mode.

Position Mode

INFO

This mode requires a yaw rate, yaw, speed and global position estimate.

This is the manual mode with the most autopilot support. The vehicle regulates its yaw rate and speed to a setpoint. If the yaw rate setpoint is zero, the controller will remember the GPS coordinates and yaw (heading) of the vehicle and use those to construct a line that the rover will then follow (course control). This offers the highest amount of disturbance rejection, which leads to the best straight line driving behavior.

StickEffect
Left stick up/downStick position sets a forward/back speed setpoint. The vehicle attempts to maintain this speed on slopes etc.
Right stick left/rightCreate a yaw rate setpoint for the control system to regulate. If this input is zero the control system will maintain the course of the rover.

For the configuration/tuning of this mode see Position mode.

Auto Modes

In auto modes the autopilot takes over control of the vehicle to run missions, return to launch, or perform other autonomous navigation tasks. For the tuning process see the configuration for Auto modes.

Mission Mode

Mission mode is an automatic mode that causes the vehicle to execute a predefined autonomous mission plan that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application, such as QGroundControl.

Mission commands

The following commands can be used in missions at time of writing (main/planned for PX4 v1.16+):

QGC mission itemCommandDescription
Mission startMAV_CMD_MISSION_STARTStarts the mission.
WaypointMAV_CMD_NAV_WAYPOINTNavigate to waypoint.
Return to launchMAV_CMD_NAV_RETURN_TO_LAUNCHReturn to the launch location.
Change speedMAV_CMD_DO_CHANGE_SPEEDChange the speed setpoint
Set launch locationMAV_CMD_DO_SET_HOMEChanges launch location to specified coordinates.
Jump to item (all)MAV_CMD_DO_JUMP (and other jump commands)Jump to specified mission item.

Return Mode

This mode uses the pure pursuit guidance logic with the launch position as goal. Return mode can be activated through the respective mission command or through the ground station UI.