diff --git a/assets/airframes/rover/rover_ackermann/ackermann_rover_guidance_structure.png b/assets/airframes/rover/rover_ackermann/ackermann_rover_guidance_structure.png
new file mode 100644
index 00000000000..26fecb5ad24
Binary files /dev/null and b/assets/airframes/rover/rover_ackermann/ackermann_rover_guidance_structure.png differ
diff --git a/en/SUMMARY.md b/en/SUMMARY.md
index d14b107b15b..1a0e9eab9b8 100644
--- a/en/SUMMARY.md
+++ b/en/SUMMARY.md
@@ -390,11 +390,11 @@
- [Helicopter (experimental)](frames_helicopter/index.md)
- [Helicopter Config/Tuning](config_heli/index.md)
- [Rovers (experimental)](frames_rover/index.md)
- - [Differential Rover](frames_rover/differential.md)
+ - [Differential Rovers](frames_rover/differential.md)
- [Drive Modes](flight_modes_rover/differential.md)
- [Configuration/Tuning](config_rover/differential.md)
- [Aion Robotics R1](frames_rover/aion_r1.md)
- - [Ackermann Rover](frames_rover/ackermann.md)
+ - [Ackermann Rovers](frames_rover/ackermann.md)
- [Drive Modes](flight_modes_rover/ackermann.md)
- [Configuration/Tuning](config_rover/ackermann.md)
- [(Deprecated) Rover Position Control](frames_rover/rover_position_control.md)
diff --git a/en/config_rover/ackermann.md b/en/config_rover/ackermann.md
index 61fe9f49562..d56f22e9af9 100644
--- a/en/config_rover/ackermann.md
+++ b/en/config_rover/ackermann.md
@@ -2,9 +2,11 @@
This topic provides a step-by-step guide for setting up your [Ackermann rover](../frames_rover/ackermann.md).
-::: info
-Many features of this module are disabled by default, and are only enabled by setting certain parameters.
-The [Tuning (basic)](#tuning-basic) section goes through the minimum setup required to start driving missions and the [Tuning (advanced)](#tuning-advanced) section outlines the remaining features and tuning variables of the module.
+Successive steps enable [drive modes](../flight_modes_rover/ackermann.md) 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
@@ -18,10 +20,6 @@ To configure the Ackermann rover frame and outputs:
![QGC screenshot showing selection of the airframe 'Generic ackermann rover'](../../assets/config/airframe/airframe_generic_rover_ackermann.png)
- ::: warning
- Do not use the _Generic Ground Vehicle (Ackermann)_ airframe as that will load the [(Deprecated) Rover Position Control](../frames_rover/rover_position_control.md) module.
- :::
-
Select the **Apply and Restart** button.
::: info
@@ -30,70 +28,201 @@ To configure the Ackermann rover frame and outputs:
3. Open the [Actuators Configuration & Testing](../config/actuators.md) to map the steering and throttle functions to flight controller outputs.
-This is sufficient to drive the the rover in [manual mode](../flight_modes_rover/ackermann.md#manual-mode) (see [Drive modes](../flight_modes_rover/ackermann.md)).
+## Manual Mode
-## Tuning (Basic)
+::: warning
+For this mode to work properly the [Basic Setup](#basic-setup) must've already been completed!
+:::
-To start driving missions navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and set the following parameters:
+The basic setup already covers the minimum setup required to use the rover in [Manual mode](../flight_modes_rover/ackermann.md#manual-mode).
-| Parameter | Description | Unit |
-| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------- | ---- |
-| [RA_WHEEL_BASE](../advanced_config/parameter_reference.md#RA_WHEEL_BASE) | Wheel-base of the rover which is measured from the back to the front wheel | m |
-| [RA_MAX_STR_ANG](../advanced_config/parameter_reference.md#RA_MAX_STR_ANG) | Maximum steering angle of the rover | deg |
-| [RA_MISS_VEL_DEF](../advanced_config/parameter_reference.md#RA_MISS_VEL_DEF) | Default velocity the rover will drive during the mission | m/s |
+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](../advanced_config/parameters.md) in QGroundControl and set the following parameters:
-![Geometric parameters](../../assets/airframes/rover/rover_ackermann/geometric_parameters.png)
+1. [RA_WHEEL_BASE](#RA_WHEEL_BASE) [m]: Measure the distance from the back to the front wheels.
+2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle.
-This is enough to start driving missions, but depending on the rover might not yet lead to satisfactory performance .
-If that is the case further tuning is required which is outlined in [Mission parameters](#mission-parameters).
+ ![Geometric parameters](../../assets/airframes/rover/rover_ackermann/geometric_parameters.png)
-## Tuning (Advanced)
+3. [RA_MAX_THR_SPEED](#RA_MAX_THR_SPEED) [m/s]: Drive the rover at full throttle and set this parameter to the observed value of the ground speed.
-To get an overview of all parameters that are related to the Ackermann rover module navigate to the _Rover Ackermann_ group in the _Parameters_ section of QGroundControl.
+ :::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](#position-mode).
+ :::
-### General Parameters
+4. [RA_MAX_ACCEL](#RA_MAX_ACCEL) [m/s^2]: Maximum acceleration you want to allow for your rover.
-These parameters affect the general behaviour of the rover.
-This will influence both auto and manual modes.
+
-| Parameter | Description | Unit |
-| ----------------------------------------------------------------------------------------------- | ------------------------------------------ | ---- |
-| [RA_MAX_SPEED](../advanced_config/parameter_reference.md#RA_MAX_SPEED) | Speed the rover drives at maximum throttle | m/s |
+ :::tip
+ This value is set to your preference, there is no general rule of thumb since it depends entirely on your rover and use case.
+ The most straightforward approach is the following: Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply.
+ From a standstill, give the rover full throttle until it reaches the maximum speed. Disarm the rover and plot the _measured_forward_speed_ from [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md).
+ Divide the maximum speed by the time it took to reach it and set this as the value for [RA_MAX_ACCEL](#RA_MAX_ACCEL).
+ Some RC rovers have enough torque to lift up if the maximum acceleration is not limited. If that is the case, set [RA_MAX_ACCEL](#RA_MAX_ACCEL) to a low value, give the rover full throttle
+ from a standstill and observe its behaviour. Increase [RA_MAX_ACCEL](#RA_MAX_ACCEL) until the rover starts to lift up during the acceleration. Set [RA_MAX_ACCEL](#RA_MAX_ACCEL) to the highest value
+ that does not cause the rover to lift up.
+ :::
-This is used for a feed-forward term on the speed controller in mission mode and necessary for the [acceleration slew rate](#slew-rates).
+5. [RA_MAX_DECEL](#RA_MAX_DECEL) [m/s^2]: Maximum deceleration you want to allow for your rover.
-#### Slew Rates
+ :::tip
+ The same [considerations](#RA_MAX_ACCEL_CONSIDERATIONS) as in the configuration of [RA_MAX_ACCEL](#RA_MAX_ACCEL) apply.
+ :::
-Slew rates limit how fast the signal that is sent to the motors is allowed to change:
+ :::info
+ This parameter is also used for the calculation of the speed setpoint during [Auto modes](#auto-modes).
+ :::
-| Parameter | Description | Unit |
-| -------------------------------------------------------------------------------------------------------- | -------------------------------------- | ----- |
-| [RA_MAX_ACCEL](../advanced_config/parameter_reference.md#RA_MAX_ACCEL) | Limit on the acceleration of the rover | m/s^2 |
-| [RA_MAX_STR_RATE](../advanced_config/parameter_reference.md#RA_MAX_STR_RATE) | Limit on the steering rate | deg/s |
+6. (Optional) [RA_MAX_STR_RATE](#RA_MAX_STR_RATE) [deg/s]: Maximum steering rate you want to allow for your rover.
-:::warning
-The slew rates are not based on measurements but on assumed linear relation between the throttle input and [RA_MAX_SPEED](#RA_MAX_SPEED) or steering input and [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) respectively.
-Therefore these two parameters have to be set for the slew rates to work!
+ :::tip
+ This value is set to your preference, there is no general rule of thumb since it depends entirely 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](#RA_MAX_STR_RATE) until you observe the steering rate to be limited by the parameter.
+ For smaller rovers you might observe the steering to be too aggressive. Set [RA_MAX_STR_RATE](#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](#acro-mode) must've already been configured!
:::
-## Mission Parameters
+To set up [Acro mode](../flight_modes_rover/ackermann.md#acro-mode) navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and set the following parameters:
-These parameters only affect vehicle in [Mission Mode](../flight_modes_rover/ackermann.md#mission-mode).
+1. [RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL): Maximum lateral acceleration you want to allow for your rover.
+
+ :::tip
+ This value is set to your preference, there is no general rule of thumb since it depends entirely on your rover and use case.
+ 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, set [RA_MAX_LAT_ACCEL](#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 in [Acro mode](../flight_modes_rover/ackermann.md#acro-mode). Increase [RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL) until the wheels of the rover start to lift up. Set [RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL) to the highest value that does not cause the rover to lift up.
+ The same approach of slowly increasing [RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL) from a small value can be taken if you encounter any of the other aforementioned issues.
+ If none of these points is a concern, do the following: In [Manual mode](#manual-mode) drive the rover at full throttle and with the maximum steering angle
+ Plot the _measured_lateral_acceleration_ from [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md) and enter the highest observed value for [RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL).
+ :::
+
+2. [RA_LAT_ACCEL_P](#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 put the rover in [Acro mode](../flight_modes_rover/ackermann.md#acro-mode) and hold the throttle stick and the right stick at a few different levels for a couple of seconds each.
+ Disarm the rover and from the flight log plot the _lateral_acceleration_setpoint_ from [RoverAckermannSetpoint](../msg_docs/RoverAckermannSetpoint.md) and the _measured_lateral_acceleration_ from [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md) over each other. Increase [RA_LAT_ACCEL_P](#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. Repeat until you are satisfied with the behaviour.
+ Note that the lateral acceleration measurement is very noise and therefor 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](#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](../flight_modes_rover/ackermann.md#acro-mode).
+
+## Position Mode
:::warning
-The parameters in [Tuning (basic)](#tuning-basic) must also be set to drive missions!
+For this mode to work properly [Acro mode](#acro-mode) must already be configured!
:::
-The module uses a control algorithm called pure pursuit, see [Pure Pursuit Guidance Logic](#pure-pursuit-guidance-logic) for the basic tuning process.
+[Position mode](../flight_modes_rover/ackermann.md#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](#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](#auto-modes).
+2. [RA_MAX_THR_SPD](#RA_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.
+ As already mentioned in the configuration of [Manual mode](../flight_modes_rover/ackermann.md#manual-mode), a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/ackermann.md#manual-mode).
+
+
+
+ ::: tip
+ To further tune this parameter, first make sure you set [RA_SPEED_P](#RA_SPEED_P) and [RA_SPEED_I](#RA_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](../flight_modes_rover/ackermann.md#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 _adjusted_forward_speed_setpoint_ and the _measured_forward_speed_ from the [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md) message over each other.
+ If the actual speed of the rover is higher than the speed setpoint, increase [RA_MAX_THR_SPD](#RA_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](../flight_modes_rover/ackermann.md#position-mode) just set this parameter to the observed ground speed at maximum throttle in [Manual mode](../flight_modes_rover/ackermann.md#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](#RA_SPEED_P) [-]: Proportional gain of the closed loop speed controller.
+
+ ::: tip
+ This parameter can be tuned the same way as [RA_MAX_THR_SPD](#RA_SPEED_TUNING).
+ If you tuned [RA_MAX_THR_SPD](#RA_MAX_THR_SPD) well, you might only need a very small value.
+ :::
+
+4. [RA_SPEED_I](#RA_SPEED_I) [-]: Integral gain for the closed loop speed controller.
-:::info
-Increasing [PP_LOOKAHD_MIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_MIN) can help to make the steering less aggressive at slow speeds.
-This can be useful especially if the [corner slow down effect](#corner-slow-down) is enabled.
+ ::: 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](#PP_LOOKAHD_GAIN): When driving in a straight line (right stick centered) position mode leverages the same path following algorithm used in [auto modes](#auto-modes) called [pure pursuit](#pure-pursuit-guidance-logic) to achieve the best possible straight line driving behaviour ([Illustration of control architecture](#pure_pursuit_controller)).
+ 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](#PP_LOOKAHD_GAIN), put the rover in [Position mode](../flight_modes_rover/ackermann.md#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](#PP_LOOKAHD_MIN): Minimum threshold for the lookahead distance used by the [pure pursuit algorithm](#pure-pursuit-guidance-logic).
+
+ ::: tip
+ Put the rover in [Position mode](../flight_modes_rover/ackermann.md#position-mode) and drive at very low speeds, if the rover starts to oscillate even though the tuning of [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN) was good for medium speeds, then increase the value of [PP_LOOKAHD_MIN](#PP_LOOKAHD_MIN).
+ :::
+
+7. [PP_LOOKAHD_MAX](#PP_LOOKAHD_MAX): Maximum threshold for the lookahead distance used by [pure pursuit](#pure-pursuit-guidance-logic).
+
+ ::: tip
+ Put the rover in [Position mode](../flight_modes_rover/ackermann.md#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](#PP_LOOKAHD_GAIN) was good for medium speeds, then decrease the value of [PP_LOOKAHD_MAX](#PP_LOOKAHD_MAX).
+ :::
+
+The rover is now ready to drive in [Position mode](../flight_modes_rover/ackermann.md#position-mode).
+
+## Auto Modes
+
+::: warning
+For this mode to work properly [Manual Mode](#manual-mode), [Acro mode](#acro-mode)and [Position mode](#position-mode) must already be configured!
:::
-### Cornering Parameters
+
+In [auto modes](../flight_modes_rover/ackermann.md#auto-modes) the autopilot takes over navigation tasks using the following control architecture:
+
+![Pure Pursuit Controller](../../assets/airframes/rover/rover_ackermann/ackermann_rover_guidance_structure.png)
+
+The required parameters are separated into the following sections:
+
+### Speed
+
+1. [RA_MISS_SPD_DEF](#RA_MISS_SPD_DEF) [m/s]: Sets the default speed for the rover during the mission.
+2. [RA_MAX_DECEL](#RA_MAX_DECEL) [m/s^2] and [RA_MAX_JERK](#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](#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](#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](#RA_MAX_JERK) parameter otherwise increase it as much as possible as it can interfere with the tuning of [RA_MAX_DECEL](#RA_MAX_DECEL).
+ These two parameters have to be tuned as a pair, repeat until you are satisfied with the behaviour.
+ :::
+
+3. Plot the _adjusted_forward_speed_setpoint_ and \_measured_forward_speed from the [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md) message over each other. If the tracking of these setpoints is not satisfactory adjust the values for [RA_SPEED_P](#RA_SPEED_P) and [RA_SPEED_I](#RA_SPEED_I).
-#### Corner cutting
+### 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](#mission-cornering-logic-info-only)).
@@ -102,32 +231,30 @@ This is done by scaling the acceptance radius based on the corner the rover has
The degree to which corner cutting is allowed can be tuned, or disabled, with the following parameters:
-| Parameter | Description | Unit |
-| -------------------------------------------------------------------------------------------------------- | ----------------------------------------------------- | ---- |
-| [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD) | Default acceptance radius | m |
-| [RA_ACC_RAD_MAX](../advanced_config/parameter_reference.md#RA_ACC_RAD_MAX) | Maximum radius the acceptance radius can be scaled to | m |
-| [RA_ACC_RAD_GAIN](../advanced_config/parameter_reference.md#RA_ACC_RAD_GAIN) | Tuning parameter | - |
-
-The tuning parameter is a multiplicand on the calculated ideal acceptance radius to account for dynamic effects.
+:::note
+The corner cutting effect is a tradeoff between how close you get to the waypoint and the smoothness of the trajectory.
+:::
-#### Corner slow down
+1. [NAV_ACC_RAD](#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](#RA_ACC_RAD_MAX) [m]: The maximum the acceptance radius can be scaled to. Set equal to [NAV_ACC_RAD](#NAV_ACC_RAD) to disable the corner cutting effect.
+3. [RA_ACC_RAD_GAIN](#RA_ACC_RAD_GAIN) [-]: This tuning parameter is a multiplicand on the [calculated ideal acceptance radius](#mission-cornering-logic-info-only) to account for dynamic effects.
-To smoothen the trajectory further and reduce the risk of the rover rolling over, the mission speed is reduced as the rover gets closer to a waypoint:
+ :::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](#RA_ACC_RAD_MAX).
+ :::
-- During cornering the rover drives at a speed that is equal to the the inverse of the acceptance radius (calculated using the [corner cutting logic](#corner-cutting)) multiplied with a tuning parameter called [RA_MISS_VEL_GAIN](#RA_MISS_VEL_GAIN).
-- 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.
- This requires [RA_MAX_ACCEL](#RA_MAX_ACCEL) and [RA_MAX_JERK](#RA_MAX_JERK) to be set.
+### Path Following
-The mission speed is constrained between a minimum allowed speed [RA_MISS_VEL_MIN](#RA_MISS_VEL_MIN) and the default mission speed [RA_MISS_VEL_DEF](#RA_MISS_VEL_DEF).
+The [pure pursuit](#pure-pursuit-guidance-logic) 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](#acro-mode) and the pure pursuit was tuned when setting up the [Position mode](#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:
-| Parameter | Description | Unit |
-| ----------------------------------------------------------------------------------------------------------- | ---------------------------------------------------- | ------- |
-| [RA_MISS_VEL_DEF](../advanced_config/parameter_reference.md#RA_MISS_VEL_DEF) | Default mission speed | $m/s$ |
-| [RA_MISS_VEL_MIN](../advanced_config/parameter_reference.md#RA_MISS_VEL_MIN) | Minimum the speed can be reduced to during cornering | $m/s$ |
-| [RA_MISS_VEL_GAIN](../advanced_config/parameter_reference.md#RA_MISS_VEL_GAIN) | Tuning parameter for the velocity reduction | - |
-| [RA_MAX_JERK](../advanced_config/parameter_reference.md#RA_MAX_JERK) | Limit for forwards acc/deceleration change. | $m/s^3$ |
+1. Plot the _lateral_acceleration_setpoint_ from [RoverAckermannSetpoint](../msg_docs/RoverAckermannSetpoint.md) and the _measured_lateral_acceleration_ from the [RoverAckermannStatus](../msg_docs/RoverAckermannStatus.md) over each other. If the tracking of these setpoints is not satisfactory adjust the values for [RA_LAT_ACCEL_P](#RA_LAT_ACCEL_P) and [RA_LAT_ACCEL_I](#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](#pure-pursuit-guidance-logic) parameters.
-### Pure Pursuit Guidance Logic
+## 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:
@@ -155,7 +282,9 @@ To summarize, the following parameters can be used to tune the controller:
| [PP_LOOKAHD_MAX](../advanced_config/parameter_reference.md#PP_LOOKAHD_MAX) | Maximum value for the look ahead radius | m |
| [PP_LOOKAHD_MIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_MIN) | Minimum value for the look ahead radius | m |
-### Mission Cornering Logic (Info only)
+## Mission Cornering Logic (Info only)
+
+### Corner Cutting
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.
@@ -181,8 +310,53 @@ $$
| $\delta_{max}$ | Maximum steer angle | m |
| $r_{acc}$ | Acceptance radius | m |
-
+ $$ v_{cor, max} = \sqrt{r \cdot a_{lat, max}} $$
+
+ with $r:$ Turning radius for the upcoming corner and $a_{lat, max}:$ Maximum lateral acceleration ([RA_MAX_LAT_ACCEL](#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 default mission speed [RA_MISS_VEL_DEF](#RA_MISS_VEL_DEF) and the speed where the maximum steering angle does not cause the rover to exceed the lateral acceleration limit:
+
+
+$$ v_{min} = \sqrt{\frac{w_b \cdot a_{lat, max}}{tan(\theta_{max})}} $$
+
+with $w_b:$ Wheel base ([RA_WHEEL_BASE](#RA_WHEEL_BASE)), $a_{lat, max}:$ Maximum lateral acceleration ([RA_MAX_LAT_ACCEL](#RA_MAX_LAT_ACCEL)) and $\theta_{max}:$ Maximum steering angle ([RA_MAX_STR_ANG](#RA_MAX_STR_ANG)).
+
+## Parameter Overview
+
+List of all parameters of the ackermann rover module:
+
+| Parameter | Description | Unit |
+| ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------- | ------- |
+| [RA_WHEEL_BASE](../advanced_config/parameter_reference.md#RA_WHEEL_BASE) | Wheel base | m |
+| [RA_MAX_STR_ANG](../advanced_config/parameter_reference.md#RA_MAX_STR_ANG) | Maximum steering angle | deg |
+| [RA_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RA_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | m/s |
+| [RA_MAX_ACCEL](../advanced_config/parameter_reference.md#RA_MAX_ACCEL) | Maximum allowed acceleration | m/s^2 |
+| [RA_MAX_DECEL](../advanced_config/parameter_reference.md#RA_MAX_DECEL) | Maximum allowed deceleration | m/s^2 |
+| [RA_MAX_JERK](../advanced_config/parameter_reference.md#RA_MAX_JERK) | Maximum allowed jerk for the rover | $m/s^3$ |
+| [RA_MAX_STR_RATE](../advanced_config/parameter_reference.md#RA_MAX_STR_RATE) | Maximum allowed steering rate | deg/s |
+| [RA_MAX_LAT_ACCEL](../advanced_config/parameter_reference.md#RA_MAX_LAT_ACCEL) | Maximum allowed lateral acceleration | m/s^2 |
+| [RA_LAT_ACCEL_P](../advanced_config/parameter_reference.md#RA_LAT_ACCEL_P) | Proportional gain for lateral acceleration controller | - |
+| [RA_LAT_ACCEL_I](../advanced_config/parameter_reference.md#RA_LAT_ACCEL_I) | Integral gain for lateral acceleration controller | - |
+| [RA_MAX_SPEED](../advanced_config/parameter_reference.md#RA_MAX_SPEED) | Maximum allowed speed | m/s |
+| [RA_SPEED_P](../advanced_config/parameter_reference.md#RA_SPEED_P) | Proportional gain for speed controller | - |
+| [RA_SPEED_I](../advanced_config/parameter_reference.md#RA_SPEED_I) | Integral gain for speed controller | - |
+| [PP_LOOKAHD_GAIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_GAIN) | Main tuning parameter for pure pursuit | - |
+| [PP_LOOKAHD_MAX](../advanced_config/parameter_reference.md#PP_LOOKAHD_MAX) | Maximum value for the look ahead radius of the pure pursuit algorithm | m |
+| [PP_LOOKAHD_MIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_MIN) | Minimum value for the look ahead radius of the pure pursuit algorithm | m |
+| [RA_MISS_SPD_DEF](../advanced_config/parameter_reference.md#RA_MISS_SPD_DEF) | Mission speed for the rover | $m/s$ |
+| [NAV_ACC_RAD](../advanced_config/parameter_reference.md#NAV_ACC_RAD) | Default acceptance radius | m |
+| [RA_ACC_RAD_MAX](../advanced_config/parameter_reference.md#RA_ACC_RAD_MAX) | Maximum radius the acceptance radius can be scaled to | m |
+| [RA_ACC_RAD_GAIN](../advanced_config/parameter_reference.md#RA_ACC_RAD_GAIN) | Tuning parameter | - |
+
+## See Also
-The following parameters affect the ackermann-steering rover:
--->
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md).
diff --git a/en/config_rover/differential.md b/en/config_rover/differential.md
index 938e7bf75c7..4407b362198 100644
--- a/en/config_rover/differential.md
+++ b/en/config_rover/differential.md
@@ -10,7 +10,7 @@ Modes will only work properly if the preceding modes have been configured.
## Basic Setup
-To start using the differential rover:
+To configure the differential rover frame and outputs:
1. Enable Rover support by flashing the [PX4 rover build](../frames_rover/index.md#flashing-the-rover-build) onto your flight controller.
Note that this is a special build that contains rover-specific modules.
@@ -22,7 +22,7 @@ To start using the differential rover:
Select the **Apply and Restart** button.
::: info
- If this airframe does not show up in the UI, it can alternatively be selected by setting the [SYS_AUTOSTART](../advanced_config/parameter_reference.md#SYS_AUTOSTART) parameter to `50000`.
+ 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](../advanced_config/parameter_reference.md#SYS_AUTOSTART) parameter to `50000`.
:::
3. Use [Actuators Configuration & Testing](../config/actuators.md) to map the motor functions to flight controller outputs.
@@ -42,6 +42,10 @@ Note that this parameter only affects this mode, not any of the following ones.
## Acro Mode
+::: warning
+For this mode to work properly the [Basic Setup](#basic-setup) must've already been completed!
+:::
+
To set up [Acro mode](../flight_modes_rover/differential.md#acro-mode) navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and set the following parameters:
1. [RD_WHEEL_TRACK](#RD_WHEEL_TRACK) [m]: Measure the distance from the centre of the right wheel to the centre of the left wheel.
@@ -61,7 +65,7 @@ To set up [Acro mode](../flight_modes_rover/differential.md#acro-mode) navigate
To further tune this parameter, first make sure you set [RD_YAW_RATE_P](#RD_YAW_RATE_P) and [RD_YAW_RATE_I](#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](../flight_modes_rover/differential.md#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 [RoverDifferentialSetpoint](../msg_docs/RoverDifferentialStatus.md) over each other.
+ Disarm the rover and from the flight log plot the _yaw_rate_setpoint_ and _actual_yaw_rate_ from the [RoverDifferentialStatus](../msg_docs/RoverDifferentialStatus.md) over each other.
If the actual yaw rate of the rover is higher than the yaw rate setpoint, increase [RD_MAX_THR_YAW_R](#RD_MAX_YAW_RATE).
If it is the other way around decrease the parameter and repeat until you are satisfied with the setpoint tracking.
:::
@@ -77,7 +81,7 @@ To set up [Acro mode](../flight_modes_rover/differential.md#acro-mode) navigate
:::
5. (Optional) [RD_YAW_RATE_I](#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 over time and that value is added to the motor command.
+ 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.
@@ -132,12 +136,11 @@ To configure set the following parameters:
This will define the stick-to-speed mapping for position mode and set an upper limit for the speed setpoint for all [auto modes](#auto-modes).
2. [RD_MAX_THR_SPD](#RD_MAX_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.
A good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/differential.md#manual-mode).
- Increase this parameter if the rover is faster than the setpoint, and decrease if the rover is slower.
::: tip
- To further tune this parameter, first make sure you set [RD_SPEED_P](#RD_YAW_RATE_P) and [RD_SPEED_I](#RD_SPEED_I) to zero.
+ To further tune this parameter, first make sure you set [RD_SPEED_P](#RD_SPEED_P) and [RD_SPEED_I](#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](../flight_modes_rover/differential.md#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](../msg_docs/RoverDifferentialSetpoint.md) message and the _actual_speed_ from the [RoverDifferentialStatus](../msg_docs/RoverDifferentialStatus.md) message over each other.
diff --git a/en/frames_rover/ackermann.md b/en/frames_rover/ackermann.md
index 08fc4a9ca96..83080d6c69e 100644
--- a/en/frames_rover/ackermann.md
+++ b/en/frames_rover/ackermann.md
@@ -1,4 +1,4 @@
-# Ackermann Rover
+# Ackermann Rovers