Basic Setup
Configure the rover frame and outputs
Enable Rover support by flashing the PX4 rover build onto your flight controller. Note that this is a special build that contains rover-specific modules.
In the Airframe configuration select the your rover type: Generic Rover Ackermann/Generic Rover Differential/Generic Rover Mecanum:
Select the Apply and Restart button.
INFO
If this airframe is not displayed and you have checked that you are using rover firmware (not the default), you can alternatively enable this frame by setting the SYS_AUTOSTART parameter directly to the following value:
Rover Type Значення Ackermann 51000
Differential 50000
Mecanum 52000
:::
- Open the Actuators Configuration & Testing to map the motor/servo functions to flight controller outputs.
That is the minimum setup to use the rover in Manual mode.
Geometric Parameters
Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below. These limits are mandatory for all other modes.
Navigate to Parameters in QGroundControl and set the parameters in the group for your frame type.
Ackermann
RA_WHEEL_BASE [m]: Measure the distance from the back to the front wheels.
RA_MAX_STR_ANG [deg]: Measure the maximum steering angle.
(Optional) RA_STR_RATE_LIM [deg/s]: Maximum steering rate you want to allow for your rover.
TIP
This value depends on your rover and use case. For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing RA_STR_RATE_LIM until you observe the steering rate to no longer be limited by the parameter. For smaller rovers you might observe the steering to be too aggressive. Set RA_STR_RATE_LIM 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.
Differential
- RD_WHEEL_TRACK [m]: Measure the distance from the centre of the right wheel to the centre of the left wheel.
Mecanum
- RM_WHEEL_TRACK [m]: Measure the distance from the centre of the right wheel to the centre of the left wheel.
Speed Parameters
RO_MAX_THR_SPEED [m/s]: Drive the rover at full throttle and set this parameter to the observed value of the ground speed.
INFO
This parameter is also used for the feed-forward term of the closed loop speed control. It will be further adjusted in the velocity tuning step.
:::
(Optional) RO_ACCEL_LIM [m/s^2]: Maximum acceleration you want to allow for your rover.
TIP
Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply. This may or may not be appropriate for your vehicle and use case.
One approach to determine an appropriate value is:
- From a standstill, give the rover full throttle until it reaches the maximum speed.
- Disarm the rover and plot the
measured_speed_body_x
from RoverVelocityStatus. - Divide the maximum speed by the time it took to reach it and set this as the value for RO_ACCEL_LIM.
Some RC rovers have enough torque to lift up if the maximum acceleration is not limited. If that is the case:
- Set RO_ACCEL_LIM to a low value, give the rover full throttle from a standstill and observe its behaviour.
- Increase RO_ACCEL_LIM until the rover starts to lift up during the acceleration.
- Set RO_ACCEL_LIM to the highest value that does not cause the rover to lift up.
:::
(Optional) RO_DECEL_LIM [m/s^2]: Maximum deceleration you want to allow for your rover.
TIP
The same considerations as in the configuration of RO_ACCEL_LIM apply.
:::
INFO
This parameter is also used for the calculation of the speed setpoint in modes that are position controlled.
You can now continue the configuration process with rate tuning.
Огляд параметрів
Параметр | Опис | Unit |
---|---|---|
RO_MAX_THR_SPEED | Speed the rover drives at maximum throttle | |
RO_ACCEL_LIM | (Optional) Maximum allowed acceleration | |
RO_DECEL_LIM | (Optional) Maximum allowed deceleration |
Ackermann Specific
Параметр | Опис | Unit |
---|---|---|
RA_WHEEL_BASE | Wheel base | |
RA_MAX_STR_ANG | Maximum steering angle | |
RA_STR_RATE_LIM | (Optional) Maximum allowed steering rate | deg/s |
Differential Specific
Параметр | Опис | Unit |
---|---|---|
RD_WHEEL_TRACK | Wheel track | m |
Mecanum Specific
Параметр | Опис | Unit |
---|---|---|
RM_WHEEL_TRACK | Wheel track | m |