Skip to content

Configuration/Tuning (Ackermann Rover)

This topic provides a step-by-step guide for setting up your Ackermann 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 Ackermann 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 the Generic Rover Ackermann:

    QGC screenshot showing selection of the airframe 'Generic ackermann rover'

    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 51000.

  3. Open the Actuators Configuration & Testing to map the steering and throttle functions to flight controller outputs.

Manual Mode

WARNING

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

The basic setup already covers the minimum setup required to use the rover in Manual mode.

However, this mode is also affected by the steering slew rate and acceleration/deceleration limits. This configuration becomes mandatory for subsequent modes, which is why we do this setup here. Navigate to Parameters in QGroundControl and set the following parameters:

  1. RA_WHEEL_BASE [m]: Measure the distance from the back to the front wheels.

  2. RA_MAX_STR_ANG [deg]: Measure the maximum steering angle.

    Geometric parameters

  3. RA_MAX_THR_SPEED [m/s]: Drive the rover at full throttle and set this parameter to the observed value of the ground speed.

    INFO

    This parameter is also used for the feed-forward term of the speed control. It will be further tuned in the configuration of Position mode.

  4. RA_MAX_ACCEL [m/s^2]: Maximum acceleration you want to allow for your rover.

    TIP

    Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply. This may or may not be appropriate for your vehicle and use case.

    One approach to determine an appropriate value is:

    1. From a standstill, give the rover full throttle until it reaches the maximum speed.
    2. Disarm the rover and plot the measured_forward_speed from RoverAckermannStatus.
    3. Divide the maximum speed by the time it took to reach it and set this as the value for RA_MAX_ACCEL.

    Some RC rovers have enough torque to lift up if the maximum acceleration is not limited. If that is the case:

    1. Set RA_MAX_ACCEL to a low value, give the rover full throttle from a standstill and observe its behaviour.
    2. Increase RA_MAX_ACCEL until the rover starts to lift up during the acceleration.
    3. Set RA_MAX_ACCEL to the highest value that does not cause the rover to lift up.
  5. RA_MAX_DECEL [m/s^2]: Maximum deceleration you want to allow for your rover.

    TIP

    The same considerations as in the configuration of RA_MAX_ACCEL apply.

    INFO

    This parameter is also used for the calculation of the speed setpoint during Auto modes.

  6. (Optional) RA_MAX_STR_RATE [deg/s]: Maximum steering rate you want to allow for your rover.

    TIP

    This value depends on your rover and use case. For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing RA_MAX_STR_RATE until you observe the steering rate to no longer be limited by the parameter. For smaller rovers you might observe the steering to be too aggressive. Set RA_MAX_STR_RATE to a low value and steer the rover at a standstill. Increase the parameter until you reach the maximum steering rate you are comfortable with.

    WARNING

    A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes.

Acro Mode

WARNING

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

To set up Acro mode configure the following parameters in QGroundControl:

  1. RA_MAX_LAT_ACCEL: Maximum lateral acceleration you want to allow for your rover.

    TIP

    Limiting the lateral acceleration is necessary if the rover is prone rolling over, loosing traction at high speeds or if passenger comfort is important. Small rovers especially can be prone to rolling over when steering aggressively at high speeds.

    If this is the case:

    1. In Acro mode, set RA_MAX_LAT_ACCEL to a small value and drive the rover at full throttle and with the right stick all the way to the left or right.
    2. Increase RA_MAX_LAT_ACCEL until the wheels of the rover start to lift up.
    3. Set RA_MAX_LAT_ACCEL to the highest value that does not cause the rover to lift up.

    If you see no need to limit the lateral acceleration, set this parameter to the maximum lateral acceleration the rover can achieve:

    1. In Manual mode drive the rover at full throttle and with the maximum steering angle.
    2. Plot the measured_lateral_acceleration from RoverAckermannStatus and enter the highest observed value for RA_MAX_LAT_ACCEL.
  2. RA_LAT_ACCEL_P [-]: Proportional gain of the closed loop lateral acceleration controller. The closed loop acceleration control will compare the lateral acceleration setpoint with the measured lateral acceleration and adapt the 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

    To tune this parameter:

    1. Put the rover in Acro mode and hold the throttle stick and the right stick at a few different levels for a couple of seconds each.
    2. Disarm the rover and from the flight log plot the lateral_acceleration_setpoint from RoverAckermannSetpoint and the measured_lateral_acceleration from RoverAckermannStatus over each other.
    3. Increase RA_LAT_ACCEL_P if the measured value does not track the setpoint fast enough or decrease it if the measurement overshoots the setpoint by too much.
    4. Repeat until you are satisfied with the behaviour.

    Note that the lateral acceleration measurement is very noisy and therefore needs to be heavily filtered. This means that the measurement is slightly delayed, so if you observe a slight offset in time between the setpoint and measurement, that is not something that can be fixed with tuning.

  3. (Optional) RA_LAT_ACCEL_I [-]: Integral gain of the closed loop lateral acceleration controller. The integral gain accumulates the error between the desired and actual lateral acceleration 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 lateral acceleration 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.

Position Mode

WARNING

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

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

To configure set the following parameters:

  1. RA_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. RA_MAX_THR_SPEED [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. As mentioned in the Manual mode configuration , 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:

    1. Set RA_SPEED_P and RA_SPEED_I to zero. This way the speed is only controlled by the feed-forward term, which makes it easier to tune.
    2. 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.
    3. Disarm the rover and from the flight log plot the adjusted_forward_speed_setpoint and the measured_forward_speed from the RoverAckermannStatus message over each other.
    4. If the actual speed of the rover is higher than the speed setpoint, increase RA_MAX_THR_SPEED. 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, 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. RA_SPEED_P [-]: Proportional gain of the closed loop speed controller.

    TIP

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

  4. RA_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 (right stick centered) 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.

    To tune this:

    1. Start with a value of 1 for PP_LOOKAHD_GAIN
    2. Put the rover in Position mode and while driving a straight line at approximately half the maximum speed observe its behaviour.
    3. 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.
    4. 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 auto modes to work properly Manual Mode, Acro modeand 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 parameter configuration is discussed in the following sections.

Speed

  1. RA_MAX_DECEL [m/s^2] and RA_MAX_JERK [m/s^3] are used to calculate a speed trajectory such that the rover reaches the next waypoint with the correct cornering speed.

    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 RA_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 RA_MAX_JERK parameter otherwise increase it as much as possible as it can interfere with the tuning of RA_MAX_DECEL.

    These two parameters have to be tuned as a pair, repeat until you are satisfied with the behaviour.

  2. Plot the adjusted_forward_speed_setpoint and measured_forward_speed from the RoverAckermannStatus message over each other. If the tracking of these setpoints is not satisfactory adjust the values for RA_SPEED_P and RA_SPEED_I.

Corner Cutting

The module employs a special cornering logic causing the rover to "cut corners" to achieve a smooth trajectory. This is done by scaling the acceptance radius based on the corner the rover has to drive (for geometric explanation see Cornering logic).

Cornering Logic

The degree to which corner cutting is allowed can be tuned, or disabled, with the following parameters:

INFO

The corner cutting effect is a tradeoff between how close you get to the waypoint and the smoothness of the trajectory.

  1. NAV_ACC_RAD [m]: Default acceptance radius. This is also used as a lower bound for the acceptance radius scaling.

  2. RA_ACC_RAD_MAX [m]: The maximum the acceptance radius can be scaled to. Set equal to NAV_ACC_RAD to disable the corner cutting effect.

  3. RA_ACC_RAD_GAIN [-]: This tuning parameter is a multiplicand on the calculated ideal acceptance radius to account for dynamic effects.

    TIP

    Initially set this parameter to 1. If you observe the rover overshooting the corner, increase this parameter until you are satisfied with the behaviour. Note that the scaling of the acceptance radius is limited by RA_ACC_RAD_MAX.

Path Following

The pure pursuit algorithm is used to calculate a lateral acceleration setpoint for the vehicle that is then close loop controlled. The close loop lateral acceleration was tuned in the configuration of the Acro 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 2 steps to take:

  1. Plot the lateral_acceleration_setpoint from RoverAckermannSetpoint and the measured_lateral_acceleration from the RoverAckermannStatus over each other. If the tracking of these setpoints is not satisfactory adjust the values for RA_LAT_ACCEL_P and RA_LAT_ACCEL_I.
  2. Step 1 ensures 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

Mission Cornering Logic (Info only)

Corner Cutting Logic

To enable a smooth trajectory, the acceptance radius of waypoints is scaled based on the angle between a line segment from the current-to-previous and current-to-next waypoints. The ideal trajectory would be to arrive at the next line segment with the heading pointing towards the next waypoint. For this purpose the minimum turning circle of the rover is inscribed tangentially to both line segments.

Cornering Logic

The acceptance radius of the waypoint is set to the distance from the waypoint to the tangential points between the circle and the line segments:

rmin=Lsin(δmax)θ=12arccos(ab|a||b|)racc=rmintan(θ)
SymbolDescriptionUnit
aVector from current to previous WPm
bVector from current to next WPm
rminMinimum turn radiusm
δmaxMaximum steer anglem
raccAcceptance radiusm

Cornering Speed

To smoothen the trajectory further and reduce the risk of the rover rolling over, the rover speed is regulated as follows:

  1. During cornering the rover drives at the following speed:

    vcor,max=ralat,max

    with r: Turning radius for the upcoming corner and alat,max: Maximum lateral acceleration (RA_MAX_LAT_ACCEL).

  2. In between waypoints (straight line) the rover speed is regulated such that it will arrive at the acceptance radius of the waypoint with the desired cornering speed.

The rover is constrained between the maximum speed RA_MAX_SPEED and the speed where the maximum steering angle does not cause the rover to exceed the lateral acceleration limit:

vmin=wbalat,maxtan(θmax)

with wb: Wheel base (RA_WHEEL_BASE), alat,max: Maximum lateral acceleration (RA_MAX_LAT_ACCEL) and θmax: Maximum steering angle (RA_MAX_STR_ANG).

Parameter Overview

List of all parameters of the ackermann rover module:

ParameterDescriptionUnit
RA_WHEEL_BASEWheel basem
RA_MAX_STR_ANGMaximum steering angledeg
RA_MAX_THR_SPEEDSpeed the rover drives at maximum throttlem/s
RA_MAX_ACCELMaximum allowed accelerationm/s^2
RA_MAX_DECELMaximum allowed decelerationm/s^2
RA_MAX_JERKMaximum allowed jerk for the roverm/s3
RA_MAX_STR_RATEMaximum allowed steering ratedeg/s
RA_MAX_LAT_ACCELMaximum allowed lateral accelerationm/s^2
RA_LAT_ACCEL_PProportional gain for lateral acceleration controller-
RA_LAT_ACCEL_IIntegral gain for lateral acceleration controller-
RA_MAX_SPEEDMaximum allowed speedm/s
RA_SPEED_PProportional gain for speed controller-
RA_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
NAV_ACC_RADDefault acceptance radiusm
RA_ACC_RAD_MAXMaximum radius the acceptance radius can be scaled tom
RA_ACC_RAD_GAINTuning parameter-

See Also