Skip to content

Position Tuning

Position tuning is required in order to use Auto modes.

WARNING

The velocity tuning must've already been completed before this step!

The position controller is responsible for autonomously guiding the vehicle to a position setpoint. These position setpoints are automatically generated by the internal PX4 auto modes (Mission, Return, GoTo, ...) or can directly be sent to the rover through the RoverPositionSetpoint.msg (External Modes). A path is generated for the rover to reach its destination, which tracked through a path following algorithm called pure pursuit.

To tune the position controller configure the parameters in the following sections (using QGroundControl).

Speed

  1. (Optional) RO_SPEED_RED: Tuning parameter for the speed reduction based on the course error. This can be used to limit the maximum allowed speed based on the difference between the current course and the bearing setpoint: $v*{max} = v*{full throttle} \cdot (1 - \theta_{normalized} \cdot k) $

    with

    • vmax: Maximum speed
    • vfullthrottle: Speed at maximum throttle RO_MAX_THR_SPEED.
    • θnormalized: Course error (Course - bearing setpoint) normalized from [0°,180°] to [0,1]
    • k: Tuning parameter RO_SPEED_RED

    INFO

    This parameter is used to calculate the speed at which the vehicle arrives at a waypoint based on the upcoming corner. Set to -1 to disable course error based speed reduction.

:::

  1. (Optional) RO_DECEL_LIM [m/s^2] and RO_JERK_LIM [m/s^3] are used to calculate a speed trajectory such that the rover reaches the next waypoint with the calculated 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 RO_DECEL_LIM parameter, if it starts slowing down too early increase the parameter.
    • If you observe a jerking motion as the rover slows down, decrease the RO_JERK_LIM parameter otherwise increase it as much as possible as it can interfere with the tuning of RO_DECEL_LIM.

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

:::

  1. Plot the adjusted_speed_body_x_setpoint and measured_speed_body_x from the RoverVelocityStatus message over each other. If the tracking of these setpoints is not satisfactory adjust the values for RO_SPEED_P and RO_SPEED_I.

Path Following

The pure pursuit algorithm is used to calculate a bearing setpoint for the vehicle that is then close loop controlled.

The following parameters are used to tune the algorithm:

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

:::

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

:::

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

:::

During any auto navigation task observe the behaviour of the rover and if you are unsatisfied with the path following, there are 2 steps to take:

  1. Check if all the setpoints (rate, attitude and velocity) are properly tracked.
  2. Further tune the path following algorithm.

Ackermann Rover Only

Ackermann rovers employ 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 Comparison

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.

:::

Corner Cutting Logic (Info only)

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(θ)
SymbolОписUnit
aVector from current to previous WPm
bVector from current to next WPm
rminMinimum turn radiusm
δmaxMaximum steer anglem
raccAcceptance radiusm

Differential Rover Only

Differential rovers employ 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.

In mission modes RD_TRANS_DRV_TRN is also used to slow down the rover to a standstill, if the transition angle between the waypoints exceeds this threshold:

Differential slow down effect

Pure Pursuit Guidance Logic (Info Only)

The desired bearing setpoints are generated using the pure pursuit algorithm.

The controller takes the intersection point between a circle around the vehicle and a line segment. When targeting a position setpoint this line is constructed from the current position to the destination or when executing a mission it 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.

Position Controller Structure (Info Only)

This section provides additional information for developers and people with experience in control system design.

The position controller uses the following structure:

Rover Position Controller

Огляд параметрів

ПараметрОписUnit
RO_SPEED_RED(Optional) Tuning parameter for the speed reduction based on the course error-
PP_LOOKAHD_GAINPure pursuit: Main tuning parameter-
PP_LOOKAHD_MAXPure pursuit: Maximum value for the look ahead radiusm
PP_LOOKAHD_MINPure pursuit: Minimum value for the look ahead radiusm

Ackermann Specific

ПараметрОписUnit
RA_ACC_RAD_MAX(Optional) Maximum radius the acceptance radius can be scaled tom
RA_ACC_RAD_GAIN(Optional) Tuning parameter for the acceptance radius scaling-

Differential Specific

ПараметрОписUnit
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