Skip to content

Drive Modes (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 rovers. Note that certain flight modes have different implementations for the specific modules.

WARNING

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

Manual Mode

The Manual mode stops the rover when the RC control sticks are centred. To manually move/drive the vehicle you move the sticks outside of the centre.

Differential-steering Rover: When under manual control the throttle and roll sticks control the speed and yaw rate of the vehicle.

Ackermann Rover: When under manual control the throttle and roll sticks control the speed and steering angle of the vehicle.

Rover Manual Sticks

Note that 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.

Acro Mode

INFO

Acro mode is only supported for differential-steering rovers.

Acro Mode is similar to Manual mode, but with closed-loop yaw rate control. In this mode, the left stick input remains open-loop for forward speed control, while the right stick input commands a desired yaw rate setpoint, which is then maintained by the rover's closed-loop control system.

  • Left Stick:

    Behavior remains the same as in manual mode, directly controlling the rover's forward speed in an open-loop manner.

  • Right Stick:

    • Centered: Rover stops rotating and tries to maintains its current heading.
    • Pushed left/right: Rover rotates counter-clockwise/clockwise at the rate commanded by the stick input, using a closed-loop controller (e.g., PID) to try to ensure the vehicle yaw rate matches the given setpoint.

See Tuning(basic) to go through the necessary setup to use acro mode for differential-steering rovers.

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

Following is the list of currently implemented and tested mission related commands:

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.
Set launch locationMAV_CMD_DO_SET_HOMEChanges launch location to specified coordinates.
Jump to itemMAV_CMD_DO_JUMP (and other jump commands)Jump to specified mission item.
Loiter (all)MAV_CMD_NAV_LOITER_UNLIM (and other loiter commands)This will simply stop the rover.

Pure Pursuit Guidance Logic

The steering and throttle setpoints are generated from the mission plan using a pure pursuit algorithm:

Pure Pursuit Algorithm

The controller takes the intersection point between a circle around the vehicle and the line segment connecting the previous and current waypoint. The radius of the circle around the vehicle is used to tune the controller and is often referred to as look-ahead distance.

The look ahead distance sets how aggressive the controller behaves and is defined as ld=vk. It depends on the velocity v of the rover and a tuning parameter k that can be set with the parameter PP_LOOKAHD_GAIN.

INFO

A lower value of PP_LOOKAHD_GAIN makes the controller more aggressive but can lead to oscillations!

The lookahead is constrained between PP_LOOKAHD_MAX and PP_LOOKAHD_MIN.

If the distance from the path to the rover is bigger than the lookahead distance, the rover will target the point on the path that is closest to the rover.

To summarize, the following parameters can be used to tune the controller:

ParameterDescriptionUnit
PP_LOOKAHD_GAINMain tuning parameter-
PP_LOOKAHD_MAXMaximum value for the look ahead radiusm
PP_LOOKAHD_MINMinimum value for the look ahead radiusm

:::note Both Ackermann and differential-steering rovers have further tuning parameters that are specific to the respective modules. :::

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.