Skip to content

Configuration/Tuning (Differential Rover)

This topic provides a step-by-step guide for setting up your Differential rover. Successive steps enable drive modes with more autopilot support and features.

WARNING

Each step is dependent on the previous steps having been completed. Modes will only work properly if the preceding modes have been configured.

Basic Setup

To configure the differential rover frame and outputs:

  1. Enable Rover support by flashing the PX4 rover build onto your flight controller. Note that this is a special build that contains rover-specific modules.

  2. In the Airframe configuration select Generic Rover Differential frame:

    QGC screenshot showing selection of the airframe 'Generic Rover Differential'

    Select the Apply and Restart button.

    INFO

    If this airframe is not displayed and you have checked that you are using rover firmware (not the default), you can alternatively enable this frame by setting the SYS_AUTOSTART parameter to 50000.

  3. Use Actuators Configuration & Testing to map the motor functions to flight controller outputs.

Manual Mode

The basic setup (above) is all that is required to use the rover in Manual mode.

INFO

In manual mode the stick inputs are directly mapped to motor commands. Especially moving the stick that controls the yaw rate all the way to one side will cause the wheels on the left and right to spin at full speed in opposite directions. Depending on the rover this can lead to a very aggressive rotation. The parameters RD_MAX_YAW_RATE and RD_MAX_THR_YAW_R can be used to scale the manual input for the yaw rate.

Acro Mode

WARNING

For this mode to work properly the Basic Setup must've already been completed!

To set up Acro mode navigate to Parameters in QGroundControl and set the following parameters:

  1. RD_WHEEL_TRACK [m]: Measure the distance from the centre of the right wheel to the centre of the left wheel.

    Wheel track

  2. RD_MAX_YAW_RATE [deg/s]: This is the maximum yaw rate you want to allow for your rover. This will define the stick-to-yaw-rate mapping for all manual modes using closed loop yaw control and set an upper limit for the yaw rate setpoint for all auto modes.

  3. RD_MAX_THR_YAW_R [m/s]: This parameter is used to calculate the feed-forward term of the closed loop yaw rate control. The controller calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. To get a good starting value for this parameter drive the rover in manual mode forwards at full throttle and note the ground speed of the vehicle. Then enter twice this value for the parameter.

    TIP

    To further tune this parameter, first make sure you set RD_YAW_RATE_P and RD_YAW_RATE_I to zero. This way the yaw rate is only controlled by the feed-forward term, which makes it easier to tune. Now put the rover in Acro mode and then move the right-stick of your controller to the right and/or left and hold it at a few different levels for a couple of seconds each. Disarm the rover and from the flight log plot the yaw_rate_setpoint and actual_yaw_rate from the RoverDifferentialStatus over each other. If the actual yaw rate of the rover is higher than the yaw rate setpoint, increase RD_MAX_THR_YAW_R. If it is the other way around decrease the parameter and repeat until you are satisfied with the setpoint tracking.

  4. RD_YAW_RATE_P [-]: Proportional gain of the closed loop yaw rate controller. Unlike the feed-forward part of the controller, the closed loop yaw rate control will compare the yaw rate setpoint with the measured yaw rate and adapt to motor commands based on the error between them. The proportional gain is multiplied with this error and that value is added to the motor command. This way disturbances like uneven grounds or external forces can be compensated.

    TIP

    This parameter can be tuned the same way as RD_MAX_THR_YAW_R. If you tuned RD_MAX_THR_YAW_R well, you might only need a very small value.

  5. (Optional) RD_YAW_RATE_I [-]: Integral gain of the closed loop yaw controller. The integral gain accumulates the error between the desired and actual yaw rate scaled by the integral gain over time and that value is added to the motor command.

    TIP

    The integrator gain is usually not necessary for the yaw rate setpoint as this is usually a fast changing value. Leave this parameter at zero unless necessary, as it can have negative side effects such as overshooting or oscillating around the setpoint.

The rover is now ready to drive in Acro mode.

Stabilized Mode

WARNING

For this mode to work properly Acro mode must've already been configured!

For Stabilized mode the controller utilizes a closed loop yaw controller, which creates a yaw rate setpoint to control the yaw when it is active:

Cascaded PID for yaw control

Unlike the closed loop yaw rate, this controller has no feed-forward term. Therefore you only need to tune the closed loop gains:

  1. RD_YAW_P [-]: Proportional gain for the closed loop yaw controller.

    TIP

    In stabilized mode the closed loop yaw control is only active when driving a straight line (no yaw rate input). To tune it set RD_YAW_I to zero and start with a value of 1 for RD_YAW_P. Put the rover into stabilized mode and move the left stick of your controller up and/or down to drive forwards/backwards. Disarm the rover and from the flight log plot the yaw_setpoint from the RoverDifferentialSetpoint message and the actual_yaw from the RoverDifferentialStatus message over each other. Increase/Decrease the parameter until you are satisfied with the setpoint tracking.

  2. RD_YAW_I [-]: Integral gain for the closed loop yaw controller.

    TIP

    For the closed loop yaw control an integrator gain is useful because this setpoint is often constant for a while and an integrator eliminates steady state errors that can cause the rover to never reach the setpoint. In Auto Modes there will be a further elaboration on why an integrator is necessary for the yaw controller.

The rover is now ready to drive in Stabilized mode.

Position Mode

WARNING

For this mode to work properly Acro mode and Stabilized mode must already be configured!

Position mode is the most advanced manual mode, utilizing closed loop yaw rate, yaw and speed control and leveraging position estimates.

To configure set the following parameters:

  1. RD_MAX_SPEED [m/s]: This is the maximum speed you want to allow for your rover. This will define the stick-to-speed mapping for position mode and set an upper limit for the speed setpoint for all auto modes.

  2. RD_MAX_THR_SPD [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands. A good starting point is the observed ground speed when the rover drives at maximum throttle in Manual mode.

    TIP

    To further tune this parameter, first make sure you set RD_SPEED_P and RD_SPEED_I to zero. This way the speed is only controlled by the feed-forward term, which makes it easier to tune. Now put the rover in Position mode and then move the left stick of your controller up and/or down and hold it at a few different levels for a couple of seconds each. Disarm the rover and from the flight log plot the forward_speed_setpoint from the RoverDifferentialSetpoint message and the actual_speed from the RoverDifferentialStatus message over each other. If the actual speed of the rover is higher than the speed setpoint, increase RD_MAX_THR_SPD. If it is the other way around decrease the parameter and repeat until you are satisfied with the setpoint tracking.

    INFO

    If your rover oscillates when driving a straight line in Position mode just set this parameter to the observed ground speed at maximum throttle in Manual mode and complete steps 5-7 first before continuing the tuning of the closed loop speed control (Steps 2-4).

  3. RD_SPEED_P [-]: Proportional gain of the closed loop speed controller.

    TIP

    This parameter can be tuned the same way as RD_MAX_THR_SPD. If you tuned RD_MAX_THR_SPD well, you might only need a very small value.

  4. RD_SPEED_I [-]: Integral gain for the closed loop speed controller.

    TIP

    For the closed loop speed control an integrator gain is useful because this setpoint is often constant for a while and an integrator eliminates steady state errors that can cause the rover to never reach the setpoint.

  5. PP_LOOKAHD_GAIN: When driving in a straight line (no yaw rate input) position mode leverages the same path following algorithm used in auto modes called pure pursuit to achieve the best possible straight line driving behaviour (Illustration of control architecture). This parameter determines how aggressive the controller will steer towards the path.

    TIP

    Decreasing the parameter makes it more aggressive but can lead to oscillations. Start with a value of 1 for PP_LOOKAHD_GAIN, put the rover in Position mode and while driving a straight line at approximately half the maximum speed observe its behaviour. If the rover does not drive in a straight line, reduce the value of the parameter, if it oscillates around the path increase the value. Repeat until you are satisfied with the behaviour.

  6. PP_LOOKAHD_MIN: Minimum threshold for the lookahead distance used by the pure pursuit algorithm.

    TIP

    Put the rover in Position mode and drive at very low speeds, if the rover starts to oscillate even though the tuning of PP_LOOKAHD_GAIN was good for medium speeds, then increase the value of PP_LOOKAHD_MIN.

  7. PP_LOOKAHD_MAX: Maximum threshold for the lookahead distance used by pure pursuit.

    TIP

    Put the rover in Position mode and drive at very high speeds, if the rover does not drive in a straight line even though the tuning of PP_LOOKAHD_GAIN was good for medium speeds, then decrease the value of PP_LOOKAHD_MAX.

The rover is now ready to drive in Position mode.

Auto Modes

WARNING

For this mode to work properly Acro mode, Stabilized mode and Position mode must already be configured!

In auto modes the autopilot takes over navigation tasks using the following control architecture:

Pure Pursuit Controller

The required parameters are separated into the following sections:

Speed

These parameters are used to calculate the speed setpoint in auto modes:

  1. RD_MAX_SPEED: Sets the default velocity (m/s) for the rover during the mission (as well as the maximum speed)..

  2. RD_MAX_DECEL (m/s2) and RD_MAX_JERK (m/s3) are used to calculate a velocity trajectory such that the rover comes to a smooth stop as it reaches a waypoint.

    TIP

    Plan a mission for the rover to drive a square and observe how it slows down when approaching a waypoint. If the rover decelerates too quickly decrease the RD_MAX_DECEL parameter, if it starts slowing down too early increase the parameter. If you observe a jerking motion as the rover slows down, decrease the RD_MAX_JERK parameter otherwise increase it as much as possible as it can interfere with the tuning of RD_MAX_DECEL. These two parameters have to be tuned as a pair, repeat until you are satisfied with the behaviour.

  3. Plot the forward_speed_setpoint from the RoverDifferentialSetpoint message and the actual_speed from the RoverDifferentialStatus message over each other. If the tracking of these setpoints is not satisfactory adjust the values for RD_SPEED_P and RD_SPEED_I.

The rover only slows down when approaching the waypoint if the angle between the line segment between the previous/current waypoint and current/next waypoint is smaller than 180° - RD_TRANS_DRV_TRN. In other words: The rover slows down only if the expected heading error towards the next waypoint when arriving at the current waypoint is below RD_TRANS_DRV_TRN.

Illustration of the activation threshold of the slow down effect

For more information on the RD_TRANS_DRV_TRN parameter see State Machine.

State Machine

The module employs the following state machine to make full use of a differential rovers ability to turn on the spot:

Differential state machine

These transition thresholds can be set with RD_TRANS_DRV_TRN and RD_TRANS_TRN_DRV.

Path Following

The pure pursuit algorithm is used to calculate a desired yaw for the vehicle that is then close loop controlled. The close loop yaw rate was tuned in the configuration of the Stabilized mode and the pure pursuit was tuned when setting up the Position mode. During any auto navigation task observe the behaviour of the rover. If you are unsatisfied with the path following, there are 3 steps to take:

  1. Plot the yaw_rate_setpoint and actual_yaw_rate from the RoverDifferentialSetpoint over each other. If the tracking of these setpoints is not satisfactory adjust the values for RD_YAW_RATE_P and RD_YAW_RATE_I.
  2. Plot the yaw_setpoint from the RoverDifferentialSetpoint message and the actual_yaw from the RoverDifferentialStatus message over each other. If the tracking of these setpoints is not satisfactory adjust the values for RD_YAW_P and RD_YAW_I.
  3. Steps 1 and 2 ensure accurate setpoint tracking, if the path following is still unsatisfactory you need to further tune the pure pursuit parameters.

Pure Pursuit Guidance Logic

The desired yaw setpoints are generated using a pure pursuit algorithm: The controller takes the intersection point between a circle around the vehicle and a line segment. In mission mode this line is usually constructed by connecting the previous and current waypoint:

Pure Pursuit Algorithm

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

Parameter Overview

List of all parameters of the differential rover module:

ParameterDescriptionUnit
RD_WHEEL_TRACKWheel trackm
RD_MAX_THR_YAW_RYaw rate turning left/right wheels at max speed in opposite directionsm/s
RD_MAX_YAW_RATEMaximum allowed yaw rate for the roverdeg/s
RD_YAW_RATE_PProportional gain for yaw rate controller-
RD_YAW_RATE_IIntegral gain for yaw rate controller-
RD_YAW_PProportional gain for yaw controller-
RD_YAW_IIntegral gain for yaw controller-
RD_MAX_SPEEDMaximum allowed speed for the roverm/s
RD_MAX_THR_SPDSpeed the rover drives at maximum throttlem/s
RD_SPEED_PProportional gain for speed controller-
RD_SPEED_IIntegral gain for speed controller-
PP_LOOKAHD_GAINMain tuning parameter for pure pursuit-
PP_LOOKAHD_MAXMaximum value for the look ahead radius of the pure pursuit algorithmm
PP_LOOKAHD_MINMinimum value for the look ahead radius of the pure pursuit algorithmm
RD_MAX_SPEEDMaximum allowed speed for the rover (and default mission speed).m/s
RD_MAX_ACCELMaximum acceleration for the roverm/s2
RD_MAX_DECELMaximum deceleration for the roverm/s2
RD_MAX_JERKMaximum jerk for the roverm/s3
RD_TRANS_DRV_TRNHeading error threshold to switch from driving to spot turningdeg
RD_TRANS_TRN_DRVHeading error threshold to switch from spot turning to drivingdeg

See Also