diff --git a/assets/airframes/rover/flight_modes/manual_controls_differential_rover.png b/assets/airframes/rover/flight_modes/manual_controls_differential_rover.png
new file mode 100644
index 000000000000..2173b2c44c4c
Binary files /dev/null and b/assets/airframes/rover/flight_modes/manual_controls_differential_rover.png differ
diff --git a/assets/airframes/rover/flight_modes/manual_inputs.png b/assets/airframes/rover/flight_modes/manual_inputs.png
index 91d8f29cb53f..8d9e3bae8ec6 100644
Binary files a/assets/airframes/rover/flight_modes/manual_inputs.png and b/assets/airframes/rover/flight_modes/manual_inputs.png differ
diff --git a/assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png b/assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png
index 3fbe6d1bfb09..17c9d11b9ce2 100644
Binary files a/assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png and b/assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png differ
diff --git a/assets/airframes/rover/flight_modes/rover_manual_controls.png b/assets/airframes/rover/flight_modes/rover_manual_controls.png
new file mode 100644
index 000000000000..94542df04e7c
Binary files /dev/null and b/assets/airframes/rover/flight_modes/rover_manual_controls.png differ
diff --git a/assets/airframes/rover/rover_ackermann/cornering_logic.png b/assets/airframes/rover/rover_ackermann/cornering_logic.png
index 544327d819aa..65eefd1a287c 100644
Binary files a/assets/airframes/rover/rover_ackermann/cornering_logic.png and b/assets/airframes/rover/rover_ackermann/cornering_logic.png differ
diff --git a/assets/airframes/rover/rover_ackermann/geometric_parameters.png b/assets/airframes/rover/rover_ackermann/geometric_parameters.png
index e70f58c5e916..fd5e4de87606 100644
Binary files a/assets/airframes/rover/rover_ackermann/geometric_parameters.png and b/assets/airframes/rover/rover_ackermann/geometric_parameters.png differ
diff --git a/assets/airframes/rover/rover_differential/cascaded_pid_for_yaw.png b/assets/airframes/rover/rover_differential/cascaded_pid_for_yaw.png
new file mode 100644
index 000000000000..e916261bcada
Binary files /dev/null and b/assets/airframes/rover/rover_differential/cascaded_pid_for_yaw.png differ
diff --git a/assets/airframes/rover/rover_differential/differential_slow_down_effect.png b/assets/airframes/rover/rover_differential/differential_slow_down_effect.png
new file mode 100644
index 000000000000..2f2ffe46b061
Binary files /dev/null and b/assets/airframes/rover/rover_differential/differential_slow_down_effect.png differ
diff --git a/assets/airframes/rover/rover_differential/differential_state_machine.png b/assets/airframes/rover/rover_differential/differential_state_machine.png
index bb54ed0dbe81..c0755ce90f68 100644
Binary files a/assets/airframes/rover/rover_differential/differential_state_machine.png and b/assets/airframes/rover/rover_differential/differential_state_machine.png differ
diff --git a/assets/airframes/rover/rover_differential/pure_pursuit_controller.png b/assets/airframes/rover/rover_differential/pure_pursuit_controller.png
new file mode 100644
index 000000000000..cc37a6c74cd4
Binary files /dev/null and b/assets/airframes/rover/rover_differential/pure_pursuit_controller.png differ
diff --git a/assets/airframes/rover/rover_differential/wheel_track.png b/assets/airframes/rover/rover_differential/wheel_track.png
index 1c38dbf44162..6c355d310b98 100644
Binary files a/assets/airframes/rover/rover_differential/wheel_track.png and b/assets/airframes/rover/rover_differential/wheel_track.png differ
diff --git a/assets/airframes/rover/rovers.png b/assets/airframes/rover/rovers.png
index cbc438f03e33..056c78fe7207 100644
Binary files a/assets/airframes/rover/rovers.png and b/assets/airframes/rover/rovers.png differ
diff --git a/en/SUMMARY.md b/en/SUMMARY.md
index 6f4d8ef7ce77..ce0632762443 100644
--- a/en/SUMMARY.md
+++ b/en/SUMMARY.md
@@ -388,10 +388,13 @@
- [Helicopter (experimental)](frames_helicopter/index.md)
- [Helicopter Config/Tuning](config_heli/index.md)
- [Rovers (experimental)](frames_rover/index.md)
- - [Drive Modes](flight_modes_rover/index.md)
- - [Differential-steering Rover](frames_rover/differential_rover.md)
+ - [Differential Rover](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_rover.md)
+ - [Ackermann Rover](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)
- [Submarines (experimental)](frames_sub/index.md)
- [BlueROV2](frames_sub/bluerov2.md)
diff --git a/en/concept/flight_modes.md b/en/concept/flight_modes.md
index 49aba2e2931b..33648e804113 100644
--- a/en/concept/flight_modes.md
+++ b/en/concept/flight_modes.md
@@ -16,7 +16,8 @@ User-facing flight mode documentation can be found in:
- [Flight Modes (Multicopter)](../flight_modes_mc/index.md)
- [Flight Modes (Fixed-Wing)](../flight_modes_fw/index.md)
- [Flight Modes (VTOL)](../flight_modes_vtol/index.md)
-- [Flight/Drive Modes (Rover)](../flight_modes_rover/index.md)
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md)
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md)
:::
diff --git a/en/frames_rover/ackermann_rover.md b/en/config_rover/ackermann.md
similarity index 77%
rename from en/frames_rover/ackermann_rover.md
rename to en/config_rover/ackermann.md
index 5eb95d3b7591..61fe9f49562b 100644
--- a/en/frames_rover/ackermann_rover.md
+++ b/en/config_rover/ackermann.md
@@ -1,21 +1,18 @@
-# Ackermann Rover
+# Configuration/Tuning (Ackermann Rover)
-
-
-An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates.
-This kind of steering is used on most commercial vehicles, including cars, trucks etc.
-
-![Axial Trail Honcho](../../assets/airframes/rover/rover_ackermann/axial_trail_honcho.png)
+This topic provides a step-by-step guide for setting up your [Ackermann rover](../frames_rover/ackermann.md).
::: info
-PX4 does not require that the vehicle uses the Ackermann geometry and will work with any front-steering rover.
+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.
:::
## Basic Setup
-To start using the ackermann rover:
+To configure the Ackermann rover frame and outputs:
-1. Enable the module by flashing the [PX4 rover build](../frames_rover/index.md#flashing-the-rover-build) onto your flight controller.
+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.
2. In the [Airframe](../config/airframe.md) configuration select the _Generic Rover Ackermann_:
@@ -33,13 +30,7 @@ To start using the ackermann rover:
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/index.md#manual-mode) (see [Drive modes](../flight_modes_rover/index.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.
-:::
+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)).
## Tuning (Basic)
@@ -62,7 +53,8 @@ To get an overview of all parameters that are related to the Ackermann rover mod
### General Parameters
-These parameters affect the general behaviour of the rover. This will influence both auto and manual modes.
+These parameters affect the general behaviour of the rover.
+This will influence both auto and manual modes.
| Parameter | Description | Unit |
| ----------------------------------------------------------------------------------------------- | ------------------------------------------ | ---- |
@@ -86,13 +78,13 @@ Therefore these two parameters have to be set for the slew rates to work!
## Mission Parameters
-These parameters only affect vehicle in [Mission Mode](../flight_modes_rover/index.md#mission-mode).
+These parameters only affect vehicle in [Mission Mode](../flight_modes_rover/ackermann.md#mission-mode).
:::warning
The parameters in [Tuning (basic)](#tuning-basic) must also be set to drive missions!
:::
-The module uses a control algorithm called pure pursuit, see [Pure Pursuit Guidance Logic](../flight_modes_rover/index.md#pure-pursuit-guidance-logic) for the basic tuning process.
+The module uses a control algorithm called pure pursuit, see [Pure Pursuit Guidance Logic](#pure-pursuit-guidance-logic) for the basic tuning process.
:::info
Increasing [PP_LOOKAHD_MIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_MIN) can help to make the steering less aggressive at slow speeds.
@@ -135,6 +127,34 @@ The mission speed is constrained between a minimum allowed speed [RA_MISS_VEL_MI
| [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$ |
+### 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](../../assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png)
+
+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 $l_d = v \cdot k$.
+It depends on the velocity $v$ of the rover and a tuning parameter $k$ that can be set with the parameter [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN).
+
+::: info
+A lower value of [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN) makes the controller more aggressive but can lead to oscillations!
+:::
+
+The lookahead is constrained between [PP_LOOKAHD_MAX](#PP_LOOKAHD_MAX) and [PP_LOOKAHD_MIN](#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:
+
+| Parameter | Description | Unit |
+| -------------------------------------------------------------------------------------------------------- | --------------------------------------- | ---- |
+| [PP_LOOKAHD_GAIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_GAIN) | Main tuning parameter | - |
+| [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)
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.
diff --git a/en/config_rover/differential.md b/en/config_rover/differential.md
new file mode 100644
index 000000000000..938e7bf75c77
--- /dev/null
+++ b/en/config_rover/differential.md
@@ -0,0 +1,305 @@
+# Configuration/Tuning (Differential Rover)
+
+This topic provides a step-by-step guide for setting up your [Differential rover](../frames_rover/differential.md).
+Successive steps enable [drive modes](../flight_modes_rover/differential.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
+
+To start using the differential rover:
+
+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.
+
+2. In the [Airframe](../config/airframe.md) configuration select _Generic Rover Differential_ frame:
+
+ ![QGC screenshot showing selection of the airframe 'Generic Rover Differential'](../../assets/config/airframe/airframe_generic_rover_differential.png)
+
+ 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`.
+ :::
+
+3. Use [Actuators Configuration & Testing](../config/actuators.md) 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](../flight_modes_rover/differential.md#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 parameter [RD_MAN_YAW_SCALE](#RD_MAN_YAW_SCALE) can be used to scale the manual input for the yaw rate.
+By reducing the parameter from the default value of 1 this behaviour can be tuned.
+Note that this parameter only affects this mode, not any of the following ones.
+:::
+
+## Acro Mode
+
+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.
+
+ ![Wheel track](../../assets/airframes/rover/rover_differential/wheel_track.png)
+
+2. [RD_MAX_YAW_RATE](#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](#auto-modes).
+3. [RD_MAX_THR_YAW_R](#RD_MAX_YAW_RATE) [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](#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.
+ 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.
+ :::
+
+4. [RD_YAW_RATE_P](#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](#RD_YAW_RATE_P_TUNING).
+ If you tuned [RD_MAX_THR_YAW_R](#RD_MAX_YAW_RATE) well, you might only need a very small value.
+ :::
+
+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.
+
+ ::: 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](../flight_modes_rover/differential.md#acro-mode).
+
+## Stabilized Mode
+
+::: warning
+For this mode to work properly [Acro mode](#acro-mode) must've already been configured!
+:::
+
+For [Stabilized mode](../flight_modes_rover/differential.md#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](../../assets/airframes/rover/rover_differential/cascaded_pid_for_yaw.png)
+
+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](#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](#RD_YAW_I) to zero and start with a value of 1 for [RD_YAW_P](#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](../msg_docs/RoverDifferentialSetpoint.md) message and the _actual_yaw_ from the [RoverDifferentialStatus](../msg_docs/RoverDifferentialStatus.md) message over each other.
+ Increase/Decrease the parameter until you are satisfied with the setpoint tracking.
+ :::
+
+2. [RD_YAW_I](#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](#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](../flight_modes_rover/differential.md#stabilized-mode).
+
+## Position Mode
+
+:::warning
+For this mode to work properly [Acro mode](#acro-mode) and [Stabilized mode](#stabilized-mode) must already be configured!
+:::
+
+[Position mode](../flight_modes_rover/differential.md#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](#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](#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.
+ 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.
+ If the actual speed of the rover is higher than the speed setpoint, increase [RD_MAX_THR_SPD](#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](../flight_modes_rover/differential.md#position-mode) just set this parameter to the observed ground speed at maximum throttle in [Manual mode](../flight_modes_rover/differential.md#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](#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](#RD_SPEED_P_TUNING).
+ If you tuned [RD_MAX_THR_SPD](#RD_MAX_THR_SPD) well, you might only need a very small value.
+ :::
+
+4. [RD_SPEED_I](#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](#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](#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/differential.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/differential.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/differential.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/differential.md#position-mode).
+
+## Auto Modes
+
+::: warning
+For this mode to work properly [Acro mode](#acro-mode), [Stabilized mode](#stabilized-mode) and [Position mode](#position-mode) must already be configured!
+:::
+
+
+In [auto modes](../flight_modes_rover/differential.md#auto-modes) the autopilot takes over navigation tasks using the following control architecture:
+
+![Pure Pursuit Controller](../../assets/airframes/rover/rover_differential/pure_pursuit_controller.png)
+
+The required parameters are separated into the following sections:
+
+### Speed
+
+These parameters are used to calculate the speed setpoint in auto modes:
+
+1. [RD_MISS_SPD_DEF](#RD_MISS_SPD_DEF): Sets the default velocity ($m/s$) for the rover during the mission.
+2. [RD_MAX_ACCEL](#RD_MAX_ACCEL) ($m/s^2$) and [RD_MAX_JERK](#RD_MAX_JERK) ($m/s^3$) 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_ACCEL](#RD_MAX_ACCEL) 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](#RD_MAX_JERK) parameter otherwise increase it as much as possible as it can interfere with the tuning of [RD_MAX_ACCEL](#RD_MAX_ACCEL).
+ 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](../msg_docs/RoverDifferentialSetpoint.md) message and the _actual_speed_ from the [RoverDifferentialStatus](../msg_docs/RoverDifferentialStatus.md) message over each other.
+ If the tracking of these setpoints is not satisfactory adjust the values for [RD_SPEED_P](#RD_SPEED_P) and [RD_SPEED_I](#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](#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](#RD_TRANS_DRV_TRN).
+
+![Illustration of the activation threshold of the slow down effect](../../assets/airframes/rover/rover_differential/differential_slow_down_effect.png)
+
+For more information on the [RD_TRANS_DRV_TRN](#RD_TRANS_DRV_TRN) parameter see [State Machine](#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](../../assets/airframes/rover/rover_differential/differential_state_machine.png)
+
+These transition thresholds can be set with [RD_TRANS_DRV_TRN](#RD_TRANS_DRV_TRN) and [RD_TRANS_TRN_DRV](#RD_TRANS_TRN_DRV).
+
+### Path Following
+
+The [pure pursuit](#pure-pursuit-guidance-logic) 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](#stabilized-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:
+
+1. Plot the _yaw_rate_setpoint_ and _actual_yaw_rate_ from the [RoverDifferentialSetpoint](../msg_docs/RoverDifferentialStatus.md) over each other.
+ If the tracking of these setpoints is not satisfactory adjust the values for [RD_YAW_RATE_P](#RD_YAW_RATE_P) and [RD_YAW_RATE_I](#RD_YAW_RATE_I).
+2. Plot the _yaw_setpoint_ from the [RoverDifferentialSetpoint](../msg_docs/RoverDifferentialSetpoint.md) message and the _actual_yaw_ from the [RoverDifferentialStatus](../msg_docs/RoverDifferentialStatus.md) message over each other.
+ If the tracking of these setpoints is not satisfactory adjust the values for [RD_YAW_P](#RD_YAW_P) and [RD_YAW_I](#RD_YAW_P).
+3. Steps 1 and 2 ensure 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
+
+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](../../assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png)
+
+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 $l_d = v \cdot k$.
+It depends on the velocity $v$ of the rover and a tuning parameter $k$ that can be set with the parameter [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN).
+
+::: info
+A lower value of [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN) makes the controller more aggressive but can lead to oscillations!
+:::
+
+The lookahead is constrained between [PP_LOOKAHD_MAX](#PP_LOOKAHD_MAX) and [PP_LOOKAHD_MIN](#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:
+
+| Parameter | Description | Unit |
+| -------------------------------------------------------------------------------------------------------- | --------------------------------------- | ---- |
+| [PP_LOOKAHD_GAIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_GAIN) | Main tuning parameter | - |
+| [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 |
+
+## Parameter Overview
+
+List of all parameters of the differential rover module:
+
+| Parameter | Description | Unit |
+| ----------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | ------- |
+| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m |
+| [RD_MAN_YAW_SCALE](../advanced_config/parameter_reference.md#RD_MAN_YAW_SCALE) | Manual yaw rate scale | - |
+| [RD_MAX_THR_YAW_R](../advanced_config/parameter_reference.md#RD_MAX_THR_YAW_R) | Yaw rate turning left/right wheels at max speed in opposite directions | m/s |
+| [RD_MAX_YAW_RATE](../advanced_config/parameter_reference.md#RD_MAX_YAW_RATE) | Maximum allowed yaw rate for the rover | deg/s |
+| [RD_YAW_RATE_P](../advanced_config/parameter_reference.md#RD_YAW_RATE_P) | Proportional gain for yaw rate controller | - |
+| [RD_YAW_RATE_I](../advanced_config/parameter_reference.md#RD_YAW_RATE_I) | Integral gain for yaw rate controller | - |
+| [RD_YAW_P](../advanced_config/parameter_reference.md#RD_YAW_P) | Proportional gain for yaw controller | - |
+| [RD_YAW_I](../advanced_config/parameter_reference.md#RD_YAW_I) | Integral gain for yaw controller | - |
+| [RD_MAX_SPEED](../advanced_config/parameter_reference.md#RD_MAX_SPEED) | Maximum allowed speed for the rover | m/s |
+| [RD_MAX_THR_SPD](../advanced_config/parameter_reference.md#RD_MAX_THR_SPD) | Speed the rover drives at maximum throttle | m/s |
+| [RD_SPEED_P](../advanced_config/parameter_reference.md#RD_SPEED_P) | Proportional gain for speed controller | - |
+| [RD_SPEED_I](../advanced_config/parameter_reference.md#RD_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 |
+| [RD_MISS_SPD_DEF](../advanced_config/parameter_reference.md#RD_MISS_SPD_DEF) | Mission speed for the rover | $m/s$ |
+| [RD_MAX_ACCEL](../advanced_config/parameter_reference.md#RD_MAX_ACCEL) | Maximum acceleration for the rover | $m/s^2$ |
+| [RD_MAX_JERK](../advanced_config/parameter_reference.md#RD_MAX_JERK) | Maximum jerk for the rover | $m/s^3$ |
+| [RD_TRANS_DRV_TRN](../advanced_config/parameter_reference.md#RD_TRANS_DRV_TRN) | Heading error threshold to switch from driving to spot turning | deg |
+| [RD_TRANS_TRN_DRV](../advanced_config/parameter_reference.md#RD_TRANS_TRN_DRV) | Heading error threshold to switch from spot turning to driving | deg |
+
+## See Also
+
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md).
diff --git a/en/flight_modes/index.md b/en/flight_modes/index.md
index 447be7e27fba..7b9f452c0d50 100644
--- a/en/flight_modes/index.md
+++ b/en/flight_modes/index.md
@@ -7,7 +7,8 @@ For information about flight modes available to specific frames see the followin
- [Flight Modes (Multicopter)](../flight_modes_mc/index.md)
- [Flight Modes (Fixed-Wing)](../flight_modes_fw/index.md)
- [Flight Modes (VTOL)](../flight_modes_vtol/index.md)
-- [Flight/Drive Modes (Rover)](../flight_modes_rover/index.md)
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md)
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md)
::: info
The mode sub-topics in this section contain information that is common to all vehicles, but may not be relevant to the normal/default setup.
diff --git a/en/flight_modes_fw/index.md b/en/flight_modes_fw/index.md
index e9eeafe9c243..457d6eff951f 100644
--- a/en/flight_modes_fw/index.md
+++ b/en/flight_modes_fw/index.md
@@ -55,4 +55,5 @@ Select the mode-specific sidebar topics for detailed technical information.
- [Basic Configuration > Flight Modes](../config/flight_mode.md) - How to map RC control switches to specific flight modes
- [Flight Modes (Multicopter)](../flight_modes_mc/index.md)
- [Flight Modes (VTOL)](../flight_modes_vtol/index.md)
-- [Flight Modes (Rover)](../flight_modes_rover/index.md)
\ No newline at end of file
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md)
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md)
\ No newline at end of file
diff --git a/en/flight_modes_mc/index.md b/en/flight_modes_mc/index.md
index 23677bbf0d05..81c9ce53ec4c 100644
--- a/en/flight_modes_mc/index.md
+++ b/en/flight_modes_mc/index.md
@@ -53,4 +53,5 @@ Select the mode-specific sidebar topics for more detailed technical information.
- [Basic Configuration > Flight Modes](../config/flight_mode.md) - How to map RC control switches to specific flight modes
- [Flight Modes (Fixed-Wing)](../flight_modes_fw/index.md)
- [Flight Modes (VTOL)](../flight_modes_vtol/index.md)
-- [Flight Modes (Rover)](../flight_modes_rover/index.md)
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md)
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md)
diff --git a/en/flight_modes_rover/ackermann.md b/en/flight_modes_rover/ackermann.md
new file mode 100644
index 000000000000..4f23daf1f2bf
--- /dev/null
+++ b/en/flight_modes_rover/ackermann.md
@@ -0,0 +1,74 @@
+# Drive Modes (Ackermann 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 Ackermann rovers.
+
+For information on mapping RC control switches to specific modes see: [Basic Configuration > Flight Modes](../config/flight_mode.md).
+
+::: warning
+Selecting any other mode than those listed below will either stop the rover or can lead to undefined behaviour.
+:::
+
+## Manual Modes
+
+Manual modes require stick inputs from the user to drive the vehicle.
+
+![Manual Controls](../../assets/airframes/rover/flight_modes/rover_manual_controls.png)
+
+The manual modes listed below provide increasing levels of autopilot support:
+
+| Mode | Features |
+| ---------------------- | -------------------------------------------------------------------- |
+| [Manual](#manual-mode) | Directly map stick inputs to motor commands, no closed loop control. |
+
+### 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.
+
+Moving the left-stick up/down controls the _forward speed_ and moving the right-stick left/right controls the _steering angle_ of the vehicle.
+
+::: info
+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.
+:::
+
+## Auto Modes
+
+In auto modes the autopilot takes over control of the vehicle to run missions, return to launch, or perform other autonomous navigation tasks.
+For the tuning process see the configuration for [Auto modes](../config_rover/ackermann.md#mission-parameters).
+
+### Mission Mode
+
+_Mission mode_ is an automatic mode that causes the vehicle to execute a predefined autonomous [mission plan](../flying/missions.md) 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](https://docs.qgroundcontrol.com/master/en/).
+
+#### Mission commands
+
+The following commands can be used in missions at time of writing (`main(PX4 v1.16+)`):
+
+| QGC mission item | Command | Description |
+| ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- |
+| Mission start | [MAV_CMD_MISSION_START](MAV_CMD_MISSION_START) | Starts the mission. |
+| Waypoint | [MAV_CMD_NAV_WAYPOINT](MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
+| Return to launch | [MAV_CMD_NAV_RETURN_TO_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
+| Delay until | [MAV_CMD_NAV_DELAY](MAV_CMD_NAV_DELAY) | The rover will stop for a specified amount of time. |
+| Change speed | [MAV_CMD_DO_CHANGE_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
+| Set launch location | [MAV_CMD_DO_SET_HOME](MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
+| Jump to item (all) | [MAV_CMD_DO_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
+| Loiter (all) | [MAV_CMD_NAV_LOITER_TIME][MAV_CMD_NAV_LOITER_TIME] (and other loiter commands) | Stop the rover for given time. Other commands stop indefinitely. |
+
+[MAV_CMD_MISSION_START]: https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START
+[MAV_CMD_NAV_WAYPOINT]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT
+[MAV_CMD_NAV_RETURN_TO_LAUNCH]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH
+[MAV_CMD_NAV_DELAY]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY
+[MAV_CMD_DO_CHANGE_SPEED]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED
+[MAV_CMD_DO_SET_HOME]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME
+[MAV_CMD_NAV_LOITER_TIME]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TIME
+[MAV_CMD_DO_JUMP]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP
+
+### Return Mode
+
+This mode uses the [pure pursuit guidance logic](../config_rover/ackermann.md#pure-pursuit-guidance-logic) with the launch position as goal.
+Return mode can be activated through the respective [mission command](#mission-commands) or through the ground station UI.
diff --git a/en/flight_modes_rover/differential.md b/en/flight_modes_rover/differential.md
new file mode 100644
index 000000000000..8b6cd6e46eed
--- /dev/null
+++ b/en/flight_modes_rover/differential.md
@@ -0,0 +1,132 @@
+# Drive Modes (Differential 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 differential rovers.
+
+For information on mapping RC control switches to specific modes see: [Basic Configuration > Flight Modes](../config/flight_mode.md).
+
+::: warning
+Selecting any other mode than those listed below will either stop the rover or can lead to undefined behaviour.
+:::
+
+## Manual Modes
+
+Manual modes require stick inputs from the user to drive the vehicle.
+
+![Manual Controls](../../assets/airframes/rover/flight_modes/manual_controls_differential_rover.png)
+
+The manual modes listed below provide increasing levels of autopilot support:
+
+| Mode | Forward speed | Yaw rate | Required measurements |
+| ------------------------------ | ------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------- |
+| [Manual](#manual-mode) | Directly map stick input to motor commands. | Directly map stick input to motor commands. | None. |
+| [Acro](#acro-mode) | Directly map stick input to motor commands. | Stick input creates a yaw rate setpoint for the control system to regulate. | Yaw rate. |
+| [Stabilized](#stabilized-mode) | Directly map stick input to motor commands. | Stick input creates a yaw rate setpoint for the control system to regulate. If this setpoint is zero (stick is centered) the control system will maintain the current yaw (heading) of the rover. | Yaw rate and yaw. |
+| [Position](#position-mode) | Stick input creates a speed setpoint for the control system to regulate. | Stick input creates a yaw rate setpoint for the control system to regulate. If this setpoint is zero (stick is centered) the control system will keep the rover driving in a straight line. | Yaw rate, yaw, speed and global position (GPS). |
+
+### Manual Mode
+
+In this mode the stick inputs are directly mapped to motor commands. 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.
+
+| Stick | Effect |
+| ---------------------- | ----------------------------------- |
+| Left stick up/down | Drive the rover forwards/backwards. |
+| Left stick centered | Zero forward speed input. |
+| Right stick left/right | Yaw the rover to the left/right. |
+| Right stick centered | Zero yaw rate input |
+
+For the configuration/tuning of this mode see [Manual mode](../config_rover/differential.md#manual-mode).
+
+### Acro Mode
+
+::: info
+This mode requires a yaw rate measurement.
+:::
+
+In this mode the vehicle regulates its yaw rate to a setpoint (but does not stabilize heading or regulate speed).
+
+| Stick | Effect |
+| ---------------------- | ------------------------------------------------------------------------------------------- |
+| Left stick up/down | Drive the rover forwards/backwards. |
+| Left stick centered | Zero forward speed input. |
+| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. |
+| Right stick centered | The control system will attempt to maintain a zero yaw rate (minimal disturbance rejection) |
+
+For the configuration/tuning of this mode see [Acro mode](../config_rover/differential.md#acro-mode).
+
+### Stabilized Mode
+
+::: info
+This mode requires a yaw rate and yaw estimate.
+:::
+
+In this mode the vehicle regulates its yaw rate to a setpoint and will maintain its heading if this setpoint is zero (but does not regulate speed).
+Compared to [Acro mode](#acro-mode), this mode is much better at driving in a straight line as it can more effectively reject disturbances.
+
+| Stick | Effect |
+| ---------------------- | -------------------------------------------------------------- |
+| Left stick up/down | Drive the rover forwards/backwards. |
+| Left stick centered | Zero forward speed input. |
+| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. |
+| Right stick centered | The control system will maintain the current heading. |
+
+For the configuration/tuning of this mode see [Stabilized mode](../config_rover/differential.md#stabilized-mode).
+
+### Position Mode
+
+::: info
+This mode requires a yaw rate, yaw, speed and global position estimate.
+:::
+
+This is the mode with the most autopilot support. The vehicle regulates its yaw rate and speed to a setpoint. If the yaw rate setpoint is zero, the controller will remember the gps coordinates and yaw (heading) of the vehicle and use those to construct a line that the rover will then follow (course control).
+This offers the highest amount of disturbance rejection, which leads to the best straight line driving behavior.
+
+| Stick | Effect |
+| ---------------------- | -------------------------------------------------------------- |
+| Left stick up/down | Create a speed setpoint for the control system to regulate. |
+| Left stick centered | Zero forward speed input. |
+| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. |
+| Right stick centered | The control system will maintain the course of the rover. |
+
+For the configuration/tuning of this mode see [Position mode](../config_rover/differential.md#position-mode).
+
+## Auto Modes
+
+In auto modes the autopilot takes over control of the vehicle to run missions, return to launch, or perform other autonomous navigation tasks.
+For the configuration/tuning of these modes see [Auto Modes](../config_rover/differential.md#auto-modes).
+
+### Mission Mode
+
+_Mission mode_ is an automatic mode in which the vehicle executes a predefined autonomous [mission plan](../flying/missions.md) 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](https://docs.qgroundcontrol.com/master/en/).
+
+#### Mission commands
+
+The following commands can be used in missions at time of writing (`main(PX4 v1.16+)`):
+
+| QGC mission item | Command | Description |
+| ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- |
+| Mission start | [MAV_CMD_MISSION_START](MAV_CMD_MISSION_START) | Starts the mission. |
+| Waypoint | [MAV_CMD_NAV_WAYPOINT](MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
+| Return to launch | [MAV_CMD_NAV_RETURN_TO_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
+| Delay until | [MAV_CMD_NAV_DELAY](MAV_CMD_NAV_DELAY) | The rover will stop for a specified amount of time. |
+| Change speed | [MAV_CMD_DO_CHANGE_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
+| Set launch location | [MAV_CMD_DO_SET_HOME](MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
+| Jump to item (all) | [MAV_CMD_DO_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
+| Loiter (all) | [MAV_CMD_NAV_LOITER_TIME][MAV_CMD_NAV_LOITER_TIME] (and other loiter commands) | Stop the rover for given time. Other commands stop indefinitely. |
+
+[MAV_CMD_MISSION_START]: https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START
+[MAV_CMD_NAV_WAYPOINT]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT
+[MAV_CMD_NAV_RETURN_TO_LAUNCH]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH
+[MAV_CMD_NAV_DELAY]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY
+[MAV_CMD_DO_CHANGE_SPEED]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED
+[MAV_CMD_DO_SET_HOME]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME
+[MAV_CMD_NAV_LOITER_TIME]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TIME
+[MAV_CMD_DO_JUMP]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP
+
+### Return Mode
+
+This mode uses the [pure pursuit guidance logic](../config_rover/differential.md#pure-pursuit-guidance-logic) with the launch position as goal.
+Return mode can be activated through the respective [mission command](#mission-commands) or through the ground station UI.
diff --git a/en/flight_modes_rover/index.md b/en/flight_modes_rover/index.md
deleted file mode 100644
index 37e6ae4a062b..000000000000
--- a/en/flight_modes_rover/index.md
+++ /dev/null
@@ -1,101 +0,0 @@
-# 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.
-
-- [Basic Configuration > Flight Modes](../config/flight_mode.md) - How to map RC control switches to specific flight modes
-
-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**](../frames_rover/differential_rover.md): When under manual control the throttle and roll sticks control the _speed_ and _yaw rate_ of the vehicle.
-
-[**Ackermann Rover**](../frames_rover/ackermann_rover.md): When under manual control the throttle and roll sticks control the _speed_ and _steering angle_ of the vehicle.
-
-![Rover Manual Sticks](../../assets/airframes/rover/flight_modes/manual_inputs.png)
-
-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](#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)](../frames_rover/differential_rover.md#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](../flying/missions.md) 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](https://docs.qgroundcontrol.com/master/en/).
-
-### Mission commands
-
-Following is the list of currently implemented and tested mission related commands:
-
-| QGC mission item | Command | Description |
-| ------------------- | --------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------- |
-| Mission start | [MAV_CMD_MISSION_START](https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START) | Starts the mission. |
-| Waypoint | [MAV_CMD_NAV_WAYPOINT](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
-| Return to launch | [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH) | Return to the launch location. |
-| Delay until | [MAV_CMD_NAV_DELAY](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY) | The rover will stop for a specified amount of time. |
-| Set launch location | [MAV_CMD_DO_SET_HOME](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
-| Jump to item | [MAV_CMD_DO_JUMP](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP) (and other jump commands) | Jump to specified mission item. |
-| Loiter (all) | [MAV_CMD_NAV_LOITER_UNLIM](https://mavlink.io/en/messages/common.html#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](../../assets/airframes/rover/flight_modes/pure_pursuit_algorithm.png)
-
-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 $l_d = v \cdot k$.
-It depends on the velocity $v$ of the rover and a tuning parameter $k$ that can be set with the parameter [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN).
-
-::: info
-A lower value of [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN) makes the controller more aggressive but can lead to oscillations!
-:::
-
-The lookahead is constrained between [PP_LOOKAHD_MAX](#PP_LOOKAHD_MAX) and [PP_LOOKAHD_MIN](#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:
-
-| Parameter | Description | Unit |
-| -------------------------------------------------------------------------------------------------------- | --------------------------------------- | ---- |
-| [PP_LOOKAHD_GAIN](../advanced_config/parameter_reference.md#PP_LOOKAHD_GAIN) | Main tuning parameter | - |
-| [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 |
-
-:::note
-Both [Ackermann](../frames_rover/ackermann_rover.md#mission-parameters) and [differential-steering](../frames_rover/differential_rover.md#tuning-mission) rovers have further tuning parameters that are specific to the respective modules.
-:::
-
-## Return Mode
-
-This mode uses the [pure pursuit guidance logic](#pure-pursuit-guidance-logic) with the launch position as goal.
-Return mode can be activated through the respective [mission command](#mission-commands) or through the ground station UI.
diff --git a/en/frames_rover/ackermann.md b/en/frames_rover/ackermann.md
new file mode 100644
index 000000000000..c8d29489053c
--- /dev/null
+++ b/en/frames_rover/ackermann.md
@@ -0,0 +1,14 @@
+# Ackermann Rover
+
+
+
+An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates.
+This kind of steering is used on most commercial vehicles, including cars, trucks etc.
+
+::: info
+PX4 does not require that the vehicle uses the Ackermann geometry and will work with any front-steering rover.
+:::
+
+![Axial Trail Honcho](../../assets/airframes/rover/rover_ackermann/axial_trail_honcho.png)
+
+See [Configuration/Tuning](../config_rover/ackermann.md) to set up your rover and [Drive Modes (RA)](../flight_modes_rover/ackermann.md) for the supported flight (aka drive) modes.
\ No newline at end of file
diff --git a/en/frames_rover/differential.md b/en/frames_rover/differential.md
new file mode 100644
index 000000000000..739a47703f98
--- /dev/null
+++ b/en/frames_rover/differential.md
@@ -0,0 +1,11 @@
+# Differential Rovers
+
+
+
+A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate.
+Forward motion is achieved by driving both wheels at the same speed in the same direction.
+Rotation is achieved by driving the wheels at different speeds in opposite directions, allowing the rover to turn on the spot.
+
+![Aion R1](../../assets/airframes/rover/aion_r1/r1_rover_no_bg.png)
+
+See [Configuration/Tuning](../config_rover/differential.md) to set up your rover and [Drive Modes (RD)](../flight_modes_rover/differential.md) for the supported flight (aka drive) modes.
\ No newline at end of file
diff --git a/en/frames_rover/differential_rover.md b/en/frames_rover/differential_rover.md
deleted file mode 100644
index 0d80afeff14e..000000000000
--- a/en/frames_rover/differential_rover.md
+++ /dev/null
@@ -1,113 +0,0 @@
-# Differential-steering Rovers
-
-
-
-:::warning
-Support for rover is [experimental](../airframes/index.md#experimental-vehicles).
-Maintainer volunteers, [contribution](../contribute/index.md) of new features, new frame configurations, or other improvements would all be very welcome!
-:::
-
-A differential-steering rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate.
-
-Forward motion is achieved by driving both wheels at the same speed in the same direction.
-Rotation is achieved by driving the wheels at different speeds in opposite directions, allowing the rover to turn on the spot.
-
-![Aion R1](../../assets/airframes/rover/aion_r1/r1_rover_no_bg.png)
-
-## Basic Setup
-
-To start using the differential-steering rover:
-
-1. Enable the module by flashing the [PX4 rover build](../frames_rover/index.md#flashing-the-rover-build) onto your flight controller.
-
-2. In the [Airframe](../config/airframe.md) configuration select the _Generic Rover Differential_:
-
- ![QGC screenshot showing selection of the airframe 'Generic Rover Differential'](../../assets/config/airframe/airframe_generic_rover_differential.png)
-
- 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`.
- :::
-
-3. Open the [Actuators Configuration & Testing](../config/actuators.md) to map the motor functions to flight controller outputs.
-
-This is sufficient to drive the the rover in [manual mode](../flight_modes_rover/index.md#manual-mode) (see [Flight modes](../flight_modes_rover/index.md)).
-
-::: info
-The parameter [RD_MAN_YAW_SCALE](../advanced_config/parameter_reference.md#RD_MAN_YAW_SCALE) can be used to scale the manual input for the yaw rate.
-:::
-
-## Tuning (Basic)
-
-This section goes through the basic parameters that need to be set to use all other features for the differential-steering rover.
-Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and set the following parameters:
-
-1. [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) [m]: Measure the distance from the center of the right wheel to the center of the left wheel.
-
- ![Wheel track](../../assets/airframes/rover/rover_differential/wheel_track.png)
-
-2. [RD_MAX_SPEED](../advanced_config/parameter_reference.md#RD_MAX_SPEED) [m/s]: In manual mode, drive the rover with full throttle and enter the observed speed as the parameter.
-3. [RD_MAX_YAW_RATE](../advanced_config/parameter_reference.md#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 in acro mode as well as setting an upper limit for the yaw rate in mission mode.
-4. [RD_YAW_RATE_P](../advanced_config/parameter_reference.md#RD_YAW_RATE_P) and [RD_YAW_RATE_I](../advanced_config/parameter_reference.md#RD_YAW_RATE_I) [-]: Tuning parameters for the closed-loop yaw rate controller.
-
- ::: info
- This can be tuned by setting all previous parameters and then setting the rover to _Acro mode_.
- Use the right stick to yaw the rover on the spot and then observe the desired and actual yaw rate in the flight log.
- Change parameters and iterate.
-
- Suggestion: Start the tuning process with [RD_YAW_RATE_I](../advanced_config/parameter_reference.md#RD_YAW_RATE_I) equal to zero and only set if necessary.
- :::
-
-This is enough to start using the rover in Acro mode.
-To start driving mission the parameters in [Tuning (Mission)](#tuning-mission) also must be set.
-
-## Tuning (Mission)
-
-:::warning
-The parameters in [Tuning (Basic)](#tuning-basic) must also be set to drive missions!
-:::
-
-The module uses a control algorithm called pure pursuit, see [Mission Mode](../flight_modes_rover/index.md#mission-mode) for the basic tuning process.
-The additional parameters are separated into the following sections:
-
-### Mission Velocity
-
-These parameters tune velocity control in missions:
-
-- [RD_MISS_SPD_DEF](#RD_MISS_SPD_DEF): Sets the default velocity ($m/s$) for the rover during the mission.
-- [RD_MAX_ACCEL](#RD_MAX_ACCEL) ($m/s^2$) and [RD_MAX_JERK](#RD_MAX_JERK) ($m/s^3$) are used to calculate a velocity trajectory such that the rover comes to a smooth stop as it reaches a waypoint.
-- [RD_SPEED_P](#RD_SPEED_P) and [RD_SPEED_I](#RD_SPEED_I) are used to tune the closed-loop velocity controller during missions.
-
-### Yaw Rate
-
-The yaw rate setpoint is calculated using the heading error in a PID controller when the pure pursuit algorithm.
-This can be tuned with [RD_YAW_P](#RD_YAW_P) and [RD_YAW_I](#RD_YAW_I).
-
-::: info
-There is some degree of overlap between this tuning and the pure pursuit controller gain set in [Mission Mode](../flight_modes_rover/index.md#mission-mode) as they both have an influence on how aggressive the rover will steer.
-:::
-
-### State Machine
-
-The module employs the following state machine to make full use of a differential-steering rovers ability to turn on the spot:
-![Differential state machine](../../assets/airframes/rover/rover_differential/differential_state_machine.png)
-
-These transition thresholds can be set with [RD_TRANS_DRV_TRN](#RD_TRANS_DRV_TRN) and [RD_TRANS_TRN_DRV](#RD_TRANS_TRN_DRV).
-
-### Parameters
-
-The following parameters affect the differential-steering rover in mission mode (overview):
-
-| Parameter | Description | Unit |
-| ----------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------- | ------- |
-| [RD_MISS_SPD_DEF](../advanced_config/parameter_reference.md#RD_MISS_SPD_DEF) | Mission speed for the rover | $m/s$ |
-| [RD_MAX_ACCEL](../advanced_config/parameter_reference.md#RD_MAX_ACCEL) | Maximum acceleration for the rover | $m/s^2$ |
-| [RD_MAX_JERK](../advanced_config/parameter_reference.md#RD_MAX_JERK) | Maximum jerk for the rover | $m/s^3$ |
-| [RD_SPEED_P](../advanced_config/parameter_reference.md#RD_SPEED_P) | Proportional gain for closed loop forward speed controller | - |
-| [RD_SPEED_I](../advanced_config/parameter_reference.md#RD_SPEED_I) | Integral gain for closed loop forward speed controller | - |
-| [RD_YAW_P](../advanced_config/parameter_reference.md#RD_YAW_P) | Proportional gain for closed loop yaw controller | - |
-| [RD_YAW_I](../advanced_config/parameter_reference.md#RD_YAW_I) | Integral gain for closed loop yaw controller | - |
-| [RD_TRANS_DRV_TRN](../advanced_config/parameter_reference.md#RD_TRANS_DRV_TRN) | Heading error threshold to switch from driving to spot turning | deg |
-| [RD_TRANS_TRN_DRV](../advanced_config/parameter_reference.md#RD_TRANS_TRN_DRV) | Heading error threshold to switch from spot turning to driving | deg |
diff --git a/en/frames_rover/index.md b/en/frames_rover/index.md
index 2b8c5763fcb7..65cfd9ea241e 100644
--- a/en/frames_rover/index.md
+++ b/en/frames_rover/index.md
@@ -11,14 +11,14 @@ Maintainer volunteers, [contribution](../contribute/index.md) of new features, n
PX4 supports the following rover types:
-- [**Differential steering**](../frames_rover/differential_rover.md): direction is controlled by moving the left- and right-side wheels at different speeds (also know as skid or tank steering).
+- [**Differential steering**](../frames_rover/differential.md): direction is controlled by moving the left- and right-side wheels at different speeds (also know as skid or tank steering).
This kind of steering is commonly used on bulldozers, tanks, and other tracked vehicles.
-- [**Ackermann steering**](../frames_rover/ackermann_rover.md): direction is controlled by pointing wheels in the direction of travel.
+- [**Ackermann steering**](../frames_rover/ackermann.md): direction is controlled by pointing wheels in the direction of travel.
This kind of steering is used on most commercial vehicles, including cars, trucks etc.
-The supported flight modes can be seen in [Flight modes](../flight_modes_rover/index.md#) and the supported frames in [Airframes Reference > Rover](../airframes/airframe_reference.md#rover).
+The supported frames can be seen in [Airframes Reference > Rover](../airframes/airframe_reference.md#rover).
-## Flashing the rover build
+## Flashing the Rover Build
Rovers use a custom build that must be flashed onto your flight controller instead of the default PX4 build:
@@ -48,7 +48,7 @@ Rovers use a custom build that must be flashed onto your flight controller inste
[Gazebo](../sim_gazebo_gz/index.md) provides simulations for both types of steering:
-- [Differential-steering rover](../sim_gazebo_gz/vehicles.md#differential-rover)
+- [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover)
- [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover)
![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png)
\ No newline at end of file
diff --git a/en/frames_rover/rover_position_control.md b/en/frames_rover/rover_position_control.md
index e89a0d66f021..dcfbd06337f4 100644
--- a/en/frames_rover/rover_position_control.md
+++ b/en/frames_rover/rover_position_control.md
@@ -4,7 +4,7 @@
::: warning
This information applies to the original generic rover module that was derived from the fixed wing controller.
-It has been replaced with new modules for [Ackermann](../frames_rover/ackermann_rover.md) and [Differential-steering](../frames_rover/differential_rover.md) rovers.
+It has been replaced with new modules for [Ackermann](../frames_rover/ackermann.md) and [Differential-steering](../frames_rover/differential.md) rovers.
This module is no longer supported and will receive no updates.
:::
diff --git a/en/getting_started/px4_basic_concepts.md b/en/getting_started/px4_basic_concepts.md
index 6ea5a9449643..350de875d06d 100644
--- a/en/getting_started/px4_basic_concepts.md
+++ b/en/getting_started/px4_basic_concepts.md
@@ -332,7 +332,8 @@ An overview of the available flight modes for each vehicle can be found below:
- [Flight Modes (Multicopter)](../flight_modes_mc/index.md)
- [Flight Modes (Fixed-Wing)](../flight_modes_fw/index.md)
- [Flight Modes (VTOL)](../flight_modes_vtol/index.md)
-- [Flight Modes (Rover)](../flight_modes_rover/index.md)
+- [Drive Modes (Differential Rover)](../flight_modes_rover/differential.md)
+- [Drive Modes (Ackermann Rover)](../flight_modes_rover/ackermann.md)
Instructions for how to set up your remote control switches to enable different flight modes is provided in [Flight Mode Configuration](../config/flight_mode.md).
diff --git a/en/releases/main.md b/en/releases/main.md
index a249212805df..18bbd5d27158 100644
--- a/en/releases/main.md
+++ b/en/releases/main.md
@@ -89,17 +89,17 @@ This release contains a major rework for the rover support in PX4:
- Complete restructure of the [rover related documentation](../frames_rover/index.md).
- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build) ([PX4-Autopilot#22675](https://github.com/PX4/PX4-Autopilot/pull/22675)).
-- New module dedicated to [differential-steering rovers](../frames_rover/differential_rover.md) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-Autopilot#23430](https://github.com/PX4/PX4-Autopilot/pull/23430))
- - The module currently supports [manual mode](../flight_modes_rover/index.md#manual-mode), [acro mode](../flight_modes_rover/index.md#acro-mode), [mission mode](../flight_modes_rover/index.md#mission-mode), [return mode](../flight_modes_rover/index.md#return-mode) and implements a [guidance state machine](../frames_rover/differential_rover.md#state-machine) to fully leverage the power of differential-steering.
-- New module dedicated to [Ackermann rovers](../frames_rover/ackermann_rover.md)
- ([PX4-Autopilot#23024](https://github.com/PX4/PX4-Autopilot/pull/23024), [PX4-Autopilot#23310](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-Autopilot#23423](https://github.com/PX4/PX4-Autopilot/pull/23423)).
- - The module currently supports [manual mode](../flight_modes_rover/index.md#manual-mode), [mission mode](../flight_modes_rover/index.md#mission-mode), [return mode](../flight_modes_rover/index.md#return-mode) and adds a number of [Ackermann specific features](../frames_rover/ackermann_rover.md#tuning-advanced).
+- New module dedicated to [differential rovers](../frames_rover/differential.md) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402), [PX4-Autopilot#23430](https://github.com/PX4/PX4-Autopilot/pull/23430) and [PX4-Autopilot#23629](https://github.com/PX4/PX4-Autopilot/pull/23629))
+ - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes).
+- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md)
+ ([PX4-Autopilot#23024](https://github.com/PX4/PX4-Autopilot/pull/23024), [PX4-Autopilot#23310](https://github.com/PX4/PX4-Autopilot/pull/23383), [PX4-Autopilot#23423](https://github.com/PX4/PX4-Autopilot/pull/23423) and [PX4-Autopilot#23572](https://github.com/PX4/PX4-Autopilot/pull/23572)).
+ - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes).
- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)).
This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover):
- Generic Differential Rover `50000`.
- Generic Ackermann Rover `51000`.
- Axial SCX10 2 Trail Honcho `51001`.
-- Library for the [pure pursuit guidance algorithm](../flight_modes_rover/index.md#pure-pursuit-guidance-logic) that is shared among the rover modules ([PX4-Autopilot#23387](https://github.com/PX4/PX4-Autopilot/pull/23387) and [PX4-Autopilot#23438](https://github.com/PX4/PX4-Autopilot/pull/23438)).
+- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by both the rover modules ([PX4-Autopilot#23387](https://github.com/PX4/PX4-Autopilot/pull/23387) and [PX4-Autopilot#23438](https://github.com/PX4/PX4-Autopilot/pull/23438)).
- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)).
- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
diff --git a/en/sim_gazebo_gz/vehicles.md b/en/sim_gazebo_gz/vehicles.md
index f6c19eaa3804..25bac42f44c1 100644
--- a/en/sim_gazebo_gz/vehicles.md
+++ b/en/sim_gazebo_gz/vehicles.md
@@ -120,7 +120,7 @@ make px4_sitl gz_standard_vtol
### Differential Rover
-[Differential-steering Rover](../frames_rover/differential_rover.md) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
+[Differential Rover](../frames_rover/differential.md) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
```sh
make px4_sitl gz_r1_rover
@@ -130,7 +130,7 @@ make px4_sitl gz_r1_rover
### Ackermann Rover
-[Ackermann Rover](../frames_rover/ackermann_rover.md) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
+[Ackermann Rover](../frames_rover/ackermann.md) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
```sh
make px4_sitl gz_rover_ackermann
diff --git a/en/sim_gazebo_gz/worlds.md b/en/sim_gazebo_gz/worlds.md
index 8d2d15e6475d..dc8c6fa90cbd 100644
--- a/en/sim_gazebo_gz/worlds.md
+++ b/en/sim_gazebo_gz/worlds.md
@@ -45,7 +45,7 @@ It is not recommended the low frame rate causes segmentation faults on some fram
## Rover
-Rover world is optimised for rovers (and will be further optimised for rovers) and is the default world for [Ackermann Rover (4012)](../frames_rover/ackermann_rover.md) (`make px4_sitl gz_rover_ackermann`) and [Differential-steering Rover ((r1-rover (4009))](../frames_rover/differential_rover.md) (`make px4_sitl gz_r1_rover`).
+Rover world is optimised for rovers (and will be further optimised for rovers) and is the default world for [Ackermann Rover (4012)](../frames_rover/ackermann.md) (`make px4_sitl gz_rover_ackermann`) and [Differential Rover ((r1-rover (4009))](../frames_rover/differential.md) (`make px4_sitl gz_r1_rover`).
[PX4-gazebo-models/main/worlds/rover.sdf](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/rover.sdf)