Skip to content

Drive Modes (Mecanum 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 mecanum 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)
  • Left stick left/right: Yaw the rover to the left/right (controlling yaw rate).
  • Right stick left/right: Drive the rover left/right (controlling speed)

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 yaw rate (despite external factors)
+ Allows maximum yaw rate to be limited.
+ Slightly better at holding a straight line in uneven terrain.
Stabilized+ Maintains heading (yaw) which makes it significantly better at holding a straight line.
Position+ Best mode for holding 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/Lateral speedYaw rateRequired measurements
ManualDirectly map stick input to motor commands.Directly map stick input to motor commands.None.
AcroDirectly map stick input to motor commands.Stick input creates a yaw rate setpoint for the control system to regulate.Yaw rate.
StabilizedDirectly map stick input to motor commands.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 maintain the current yaw (heading) of the rover.Yaw rate and yaw.
PositionStick input creates a velocity 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, velocity 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/downStick position directly sets speed forward/backward.
Left stick left/rightStick position directly sets yaw rate in left/right direction.
Right stick left/rightStick position directly sets speed left/right.

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

Acro Mode

INFO

This mode requires a yaw rate measurement.

The vehicle regulates its yaw rate (Left stick left/right) to a setpoint, and a maximum yaw rate can also be specified. Heading and speed are not controlled.

Compared to Manual mode this introduces the following new features:

  • The yaw rate control ensures that the rover turns at the requested rate even on different surfaces and due to other external forces (such as wind).
  • Slightly better at driving in a straight line because if the input is zero PX4 will attempt to maintain a zero yaw rate. This is resistant to minor disturbances.
  • Upper limit for the yaw rate can be used to tune how aggressive the rover turns.
StickEffect
Left stick up/downStick position directly sets speed forward/backward.
Left stick left/rightStick position sets yaw-rate setpoint. The vehicle will track the setpoint irrespective of uneven surfaces or other external forces. If the input is zero the control system will attempt to maintain a zero yaw rate.
Right stick left/rightStick position directly sets speed left/right.

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

Stabilized Mode

INFO

This mode requires a yaw rate and yaw estimate.

The vehicle regulates its yaw rate to a setpoint, and a maximum yaw rate can also be specified. The vehicle regulates its yaw to a setpoint when the yaw rate setpoint is zero, maintaining the heading. Speed is not controlled.

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/downStick position directly sets speed forward/backward.
Left stick left/rightStick position sets yaw-rate setpoint. The vehicle will track the setpoint irrespective of uneven surfaces or other external forces. If this input is zero the control system will maintain the current yaw (heading).
Right stick left/rightStick position directly sets speed left/right.

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 mode with the most autopilot support.

The vehicle regulates its yaw rate to a setpoint, and a maximum yaw rate can also be specified. The path is maintained when the yaw rate setpoint is zero using global position (the controller constructs a line in the direction of the velocity input (forward + lateral speed) that the rover will then follow by tracking the global position). Speed is regulated to a setpoint, and a maximum value can be set.

Compared to Stabilized Mode this introduces the following features:

  • Upper limit for the speed (see Position Mode) to tune how fast the rover is allowed to drive.
  • The speed control ensures that the rover drives the requested speed even under disturbances (i.e. driving up a hill, against wind, with a heavier payload etc.).
  • The course control leads to the best straight line driving behaviour, as the vehicle will follow the intended path of the vehicle and return to it if forced off-track This is much better than stabilized mode, which can be forced off the intended track by disturbances.
StickEffect
Left stick up/downStick position sets a forward/back speed setpoint. The vehicle attempts to maintain this speed on slopes etc.
Left 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.
Right stick left/rightStick position sets a lateral speed setpoint. The vehicle attempts to maintain this speed on slopes etc.

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 configuration/tuning of these modes see Auto Modes.

Mission Mode

Mission mode is an automatic mode in which the vehicle executes 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(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.
Delay untilMAV_CMD_NAV_DELAYThe rover will stop for a specified amount of time.
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.
Loiter (all)MAV_CMD_NAV_LOITER_TIME (and other loiter commands)Stop the rover for given time. Other commands stop indefinitely.

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.