Compare commits

..

20 Commits

Author SHA1 Message Date
chfriedrich98 25386c28d5 docs: rover: small improvements 2025-10-01 12:10:49 +02:00
chfriedrich98 1b3edcd704 docs: rover developer guide 2025-10-01 11:34:45 +02:00
chfriedrich98 83e1c07e83 docs: hiwonder rovers setup guide 2025-09-30 14:55:13 +02:00
chfriedrich98 ffff79b306 rover: add hiwonder rover airframes 2025-09-30 14:55:13 +02:00
chfriedrich98 8a27b1a253 docs: rover simulation 2025-09-30 14:53:54 +02:00
chfriedrich98 1ff7657b04 rover: update simulation airframes 2025-09-30 14:53:54 +02:00
chfriedrich98 208d90a10c gz: update submodule 2025-09-30 14:53:54 +02:00
Matthias Grob 4d2170c13e docs/failure_injection: motor off requires CA_FAILURE_MODE to be set 2025-09-30 11:23:09 +02:00
Matthias Grob e59afce5db Enable directly injecting motor failures using e.g. failure motor off -i 1
Only if SYS_FAILURE_EN is enabled and CA_FAILURE_MODE is > 0.
2025-09-30 11:23:09 +02:00
Matthias Grob 786e0a12c2 FailureInjector simplification rework 2025-09-30 11:23:09 +02:00
Matthias Grob cefa41f85c failure command: fix array bound seg fault with e.g. failure motor -i 1 2025-09-30 11:23:09 +02:00
Matthias Grob 7f2a67a588 Commander: split out failure injection class into its own file 2025-09-30 11:23:09 +02:00
Jacob Dahl bacb30650c uavcan: don't init ESC if UAVCAN_ENABLE isn't set for ESC 2025-09-29 15:40:33 -04:00
Daniel Agar 900a5ede01 ekf2: range height skip "unhealthy" samples, but respect timeout (#25634)
* ekf2: range height skip "unhealthy" samples, but respect timeout

 - we should never directly use an "unhealthy" range finder sample for
   state corrections or resets, but we also shouldn't immediately abort
   active rng_hgt until the timeout has passed

* check starting_conditions_passing once

---------

Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
2025-09-29 11:23:37 -08:00
Alexander Lerach 03e6f40995 nuttx submodule update (dcache fix)
* nuttx submodule update (dcache fix)
2025-09-29 18:04:26 +02:00
airpixel-cz 2b0ea50d16 mavlink: parameters: fix camera and cannode param message routing 2025-09-26 23:16:05 -08:00
Daniel Agar 7eec4c9814 ekf2: fix gravity aid src fused flag 2025-09-26 11:45:54 -04:00
Matthias Grob 053cc9aecc Fix newlines broken from #25499 66b07d8219 2025-09-26 14:01:55 +02:00
chfriedrich98 66b07d8219 Docs: Rover API (#25499)
* docs: add RoverSetpointTypes

* docs: add rover api

* docs: remove rover offboard mavlink support

* docs: fix broken links

* Apply suggestion from @hamishwillee

---------

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
2025-09-26 10:33:35 +10:00
Sriram Kanagalingham 5023174715 tools: mavlink_shell: fix backspace handling
Changed ASCII command from ASCII #127 to ASCII #8

Good: Changed ASCII command from ASCII #127 to ASCII #8

Reported-by: jsm09a <https://github.com/jsm09a>

Signed-off-by: Siri <sriramj2@hotmail.com>
2025-09-25 13:14:13 -08:00
77 changed files with 1066 additions and 350 deletions
@@ -17,6 +17,7 @@ param set-default NAV_ACC_RAD 0.5
param set-default RD_WHEEL_TRACK 0.6
param set-default RD_TRANS_DRV_TRN 0.785398
param set-default RD_TRANS_TRN_DRV 0.174533
param set-default RD_YAW_STK_GAIN 0.6
# Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
@@ -25,6 +26,8 @@ param set-default RO_YAW_RATE_LIM 250
param set-default RO_YAW_ACCEL_LIM 400
param set-default RO_YAW_DECEL_LIM 800
param set-default RO_YAW_RATE_CORR 1
param set-default RO_YAW_EXPO 0.85
param set-default RO_YAW_SUPEXPO 0.3
# Attitude Control Parameters
param set-default RO_YAW_P 5
@@ -1,5 +1,5 @@
#!/bin/sh
# @name Rover Ackermann
# @name Generic Ackermann Rover
# @type Rover
# @class Rover
@@ -14,30 +14,32 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge
param set-default NAV_ACC_RAD 0.5
# Ackermann Parameters
param set-default RA_WHEEL_BASE 0.321
param set-default RA_WHEEL_BASE 0.5
param set-default RA_ACC_RAD_GAIN 2
param set-default RA_ACC_RAD_MAX 3
param set-default RA_ACC_RAD_MAX 1.5
param set-default RA_MAX_STR_ANG 0.5236
param set-default RA_STR_RATE_LIM 360
# Rover Control Parameters
param set-default RO_ACCEL_LIM 3
param set-default RO_DECEL_LIM 6
param set-default RO_JERK_LIM 15
param set-default RO_MAX_THR_SPEED 3.1
# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.1
param set-default RO_YAW_RATE_P 1
param set-default RO_YAW_RATE_LIM 180
# Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
param set-default RO_YAW_RATE_P 0.25
param set-default RO_YAW_RATE_LIM 130
param set-default RO_YAW_ACCEL_LIM 800
param set-default RO_YAW_DECEL_LIM 800
param set-default RO_YAW_RATE_CORR 1
param set-default RO_YAW_EXPO 0.85
param set-default RO_YAW_SUPEXPO 0.3
# Rover Attitude Control Parameters
# Attitude Control Parameters
param set-default RO_YAW_P 3
# Rover Velocity Control Parameters
param set-default RO_SPEED_LIM 3
param set-default RO_SPEED_I 0.1
# Velocity Control Parameters
param set-default RO_ACCEL_LIM 4
param set-default RO_DECEL_LIM 6
param set-default RO_JERK_LIM 10
param set-default RO_MAX_THR_SPEED 3.1
param set-default RO_SPEED_LIM 2.5
param set-default RO_SPEED_I 0.01
param set-default RO_SPEED_P 1
param set-default RO_SPEED_RED 1
@@ -48,8 +50,8 @@ param set-default PP_LOOKAHD_MIN 1
# Wheels
param set-default SIM_GZ_WH_FUNC1 101
param set-default SIM_GZ_WH_MIN1 0
param set-default SIM_GZ_WH_MAX1 200
param set-default SIM_GZ_WH_MIN1 70
param set-default SIM_GZ_WH_MAX1 130
param set-default SIM_GZ_WH_DIS1 100
# Steering
@@ -1,5 +1,5 @@
#!/bin/sh
# @name Aion Robotics R1 Rover
# @name Generic Mecanum Rover
# @type Rover
# @class Rover
@@ -7,14 +7,15 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=rover}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover_mecanum}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=rover_mecanum}
param set-default SIM_GZ_EN 1 # Gazebo bridge
param set-default NAV_ACC_RAD 0.5
# Mecanum Parameters
param set-default RM_WHEEL_TRACK 0.3
param set-default RM_WHEEL_TRACK 0.6
param set-default RM_YAW_STK_GAIN 0.6
# Rover Control Parameters
param set-default RO_ACCEL_LIM 3
@@ -29,15 +30,21 @@ param set-default RO_YAW_RATE_LIM 120
param set-default RO_YAW_ACCEL_LIM 240
param set-default RO_YAW_DECEL_LIM 1000
param set-default RO_YAW_RATE_CORR 1.75
param set-default RO_YAW_EXPO 0.85
param set-default RO_YAW_SUPEXPO 0.3
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Velocity Control Parameters
param set-default RO_SPEED_LIM 2
param set-default RO_SPEED_I 0.5
param set-default RO_SPEED_P 1
param set-default RO_SPEED_RED 1
# Velocity Control Parameters
param set-default RO_ACCEL_LIM 4
param set-default RO_DECEL_LIM 6
param set-default RO_JERK_LIM 10
param set-default RO_MAX_THR_SPEED 3.1
param set-default RO_SPEED_LIM 2.5
param set-default RO_SPEED_I 0.01
param set-default RO_SPEED_P 0.1
param set-default RO_SPEED_RED 0.5
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 0.5
@@ -48,24 +55,24 @@ param set-default PP_LOOKAHD_MIN 1
param set-default SENS_EN_MAGSIM 1
# Actuator mapping
param set-default SIM_GZ_WH_FUNC1 102 # right wheel front
param set-default SIM_GZ_WH_FUNC1 104 # left wheel back
param set-default SIM_GZ_WH_MIN1 70
param set-default SIM_GZ_WH_MAX1 130
param set-default SIM_GZ_WH_DIS1 100
param set-default SIM_GZ_WH_FUNC2 101 # left wheel front
param set-default SIM_GZ_WH_FUNC2 103 # right wheel back
param set-default SIM_GZ_WH_MIN2 70
param set-default SIM_GZ_WH_MAX2 130
param set-default SIM_GZ_WH_DIS2 100
param set-default SIM_GZ_WH_FUNC3 104 # right wheel back
param set-default SIM_GZ_WH_FUNC3 102 # left wheel front
param set-default SIM_GZ_WH_MIN3 70
param set-default SIM_GZ_WH_MAX3 130
param set-default SIM_GZ_WH_DIS3 100
param set-default SIM_GZ_WH_FUNC4 103 # left wheel back
param set-default SIM_GZ_WH_FUNC4 101 # right wheel front
param set-default SIM_GZ_WH_MIN4 70
param set-default SIM_GZ_WH_MAX4 130
param set-default SIM_GZ_WH_DIS4 100
param set-default SIM_GZ_WH_REV 10
param set-default SIM_GZ_WH_REV 0
@@ -80,10 +80,8 @@ px4_add_romfs_files(
4009_gz_r1_rover
4010_gz_x500_mono_cam
4011_gz_lawnmower
4012_gz_rover_ackermann
4013_gz_x500_lidar_2d
4014_gz_x500_mono_cam_down
4015_gz_r1_rover_mecanum
4016_gz_x500_lidar_down
4017_gz_x500_lidar_front
4018_gz_quadtailsitter
@@ -114,6 +112,8 @@ px4_add_romfs_files(
17002_flightgear_tf-g2
50000_gz_rover_differential
51000_gz_rover_ackermann
52000_gz_rover_mecanum
60002_gz_uuv_bluerov2_heavy
@@ -0,0 +1,45 @@
#!/bin/sh
#
# @name Hiwonder Tracked
#
# @url https://www.hiwonder.com/products/suspended-shock-absorbing-tracked-chassis?variant=40378709835863
#
# @type Rover
# @class Rover
#
. ${R}etc/init.d/rc.rover_differential_defaults
param set-default HIWONDER_EMM_EN 1 # Enable motor driver
param set-default BAT1_N_CELLS 3
param set-default NAV_ACC_RAD 0.5
# Differential Parameters
param set-default RD_WHEEL_TRACK 0.16
param set-default RD_TRANS_DRV_TRN 0.785398
param set-default RD_TRANS_TRN_DRV 0.0872665
# Rover Rate Control Parameters
param set-default RO_YAW_EXPO 0.2
param set-default RO_YAW_SUPEXPO 0.1
param set-default RO_YAW_RATE_I 0.1
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 140
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Velocity Control Parameters
param set-default RO_ACCEL_LIM 1
param set-default RO_DECEL_LIM 1
param set-default RO_JERK_LIM 10
param set-default RO_MAX_THR_SPEED 0.3
param set-default RO_SPEED_LIM 0.28
param set-default RO_SPEED_I 0.05
param set-default RO_SPEED_P 0.1
param set-default RO_SPEED_RED 1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
@@ -0,0 +1,46 @@
#!/bin/sh
#
# @name Hiwonder Ackermann
#
# @url https://www.hiwonder.com/products/ackermann-steering-chassis?variant=40382428348503
#
# @type Rover
# @class Rover
#
. ${R}etc/init.d/rc.rover_ackermann_defaults
param set-default HIWONDER_EMM_EN 1 # Enable motor driver
param set-default BAT1_N_CELLS 3
param set-default NAV_ACC_RAD 0.5
# Ackermann Parameters
param set-default RA_WHEEL_BASE 0.17
param set-default RA_ACC_RAD_GAIN 1
param set-default RA_ACC_RAD_MAX 1
param set-default RA_MAX_STR_ANG 0.698132
# Rover Rate Control Parameters
param set-default RO_YAW_EXPO 0.6
param set-default RO_YAW_SUPEXPO 0.3
param set-default RO_YAW_RATE_I 0.1
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 150
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Velocity Control Parameters
param set-default RO_ACCEL_LIM 1.6
param set-default RO_DECEL_LIM 3
param set-default RO_JERK_LIM 10
param set-default RO_MAX_THR_SPEED 1.2
param set-default RO_SPEED_LIM 1.1
param set-default RO_SPEED_I 0.05
param set-default RO_SPEED_P 0.1
param set-default RO_SPEED_RED 1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
@@ -0,0 +1,43 @@
#!/bin/sh
#
# @name Hiwonder Mecanum
#
# @url https://www.hiwonder.com/products/large-metal-4wd-vehicle-chassis-green
#
# @type Rover
# @class Rover
#
. ${R}etc/init.d/rc.rover_mecanum_defaults
param set-default HIWONDER_EMM_EN 1 # Enable motor driver
param set-default BAT1_N_CELLS 3
param set-default NAV_ACC_RAD 0.5
# Mecanum Parameters
param set-default RM_WHEEL_TRACK 0.16
# Rover Rate Control Parameters
param set-default RO_YAW_EXPO 0.2
param set-default RO_YAW_SUPEXPO 0.1
param set-default RO_YAW_RATE_I 0.1
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 130
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Velocity Control Parameters
param set-default RO_ACCEL_LIM 0.9
param set-default RO_DECEL_LIM 1.2
param set-default RO_JERK_LIM 10
param set-default RO_MAX_THR_SPEED 0.5
param set-default RO_SPEED_LIM 0.45
param set-default RO_SPEED_I 0.05
param set-default RO_SPEED_P 0.1
param set-default RO_SPEED_RED 1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
@@ -145,6 +145,7 @@ if(CONFIG_MODULES_ROVER_DIFFERENTIAL)
# [50000, 50999] Differential rovers
50000_generic_rover_differential
50001_aion_robotics_r1_rover
50002_hiwonder_tracked
)
endif()
@@ -153,6 +154,7 @@ if(CONFIG_MODULES_ROVER_ACKERMANN)
# [51000, 51999] Ackermann rovers
51000_generic_rover_ackermann
51001_axial_scx10_2_trail_honcho
51002_hiwonder_ackermann
)
endif()
@@ -160,6 +162,7 @@ if(CONFIG_MODULES_ROVER_MECANUM)
px4_add_romfs_files(
# [52000, 52999] Mecanum rovers
52000_generic_rover_mecanum
52001_hiwonder_mecanum
)
endif()
+1 -1
View File
@@ -191,7 +191,7 @@ def main():
cur_history_index = len(command_history)
mav_serialport.write(cur_line+'\n')
cur_line = ''
elif ord(ch) == 127: # backslash
elif ord(ch) == 8: # backspace
if len(cur_line) > 0:
erase_last_n_chars(1)
cur_line = cur_line[:-1]
Binary file not shown.

Before

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 171 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 271 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 74 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 236 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 263 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 648 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 306 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 46 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 223 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 53 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 31 KiB

After

Width:  |  Height:  |  Size: 77 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.6 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.1 MiB

After

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.2 MiB

After

Width:  |  Height:  |  Size: 47 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.1 MiB

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.1 MiB

After

Width:  |  Height:  |  Size: 13 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 48 KiB

After

Width:  |  Height:  |  Size: 24 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 190 KiB

After

Width:  |  Height:  |  Size: 111 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 724 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 18 KiB

After

Width:  |  Height:  |  Size: 67 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 22 KiB

After

Width:  |  Height:  |  Size: 60 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 64 KiB

+7 -2
View File
@@ -414,10 +414,15 @@
- [Basic Setup](config_rover/basic_setup.md)
- [Rate Tuning](config_rover/rate_tuning.md)
- [Attitude Tuning](config_rover/attitude_tuning.md)
- [Velocity Tuning](config_rover/velocity_tuning.md)
- [Speed Tuning](config_rover/speed_tuning.md)
- [Position Tuning](config_rover/position_tuning.md)
- [Apps & API](flight_modes_rover/api.md)
- [Complete Vehicles](complete_vehicles_rover/index.md)
- [Aion Robotics R1](complete_vehicles_rover/aion_r1.md)
- [Hiwonder Ackermann Chassi](complete_vehicles_rover/hiwonder_ackermann.md)
- [Hiwonder Tracked Chassi](complete_vehicles_rover/hiwonder_tracked.md)
- [Hiwonder Mecanum Chassi](complete_vehicles_rover/hiwonder_mecanum.md)
- [Aion Robotics R1 (Discontinued)](complete_vehicles_rover/aion_r1.md)
- [Developer Guide](frames_rover/developer_guide.md)
- [Submarines (experimental)](frames_sub/index.md)
- [BlueROV2](frames_sub/bluerov2.md)
- [Airframes Reference](airframes/airframe_reference.md)
@@ -0,0 +1,98 @@
# Hiwonder Ackermann
The [Hiwonder Ackermann](https://www.hiwonder.com/products/ackermann-steering-chassis?variant=40382428348503) rover is a bare-bones platform including a chassi, four wheels, two [motors with encoders](https://www.hiwonder.com/products/hall-encoder-dc-geared-motor?variant=40451123675223), a servo and a [motor driver board](https://www.hiwonder.com/products/4-channel-encoder-motor-driver).
The chassi offers many mounting points, providing the flexibility to attach your own flight controller, sensors and other payload.
![Hiwonder Ackermann](../../assets/airframes/rover/hiwonder_rovers/hiwonder_ackermann.png)
This documentation illustrates the setup of the rover and the configuration of the actuators.
## Parts List
::: info
The specific hardware used here only serves to examplify the process and can be easily replaced with what you have access to.
Ensure that the parts are compatible, including the ports available on your flight controller, and adapt the wiring to your hardware.
:::
The following parts are used in this build:
- Frame: [Hiwonder Ackermann Chassi](https://www.hiwonder.com/products/ackermann-steering-chassis?variant=40382428348503)
- Flight Controller: [Auterion Skynode S](https://auterion.com/product/skynode-s/) (Alternatives: [Flight Controllers](../flight_controller/index.md)).
- Receiver: [TBS Crossfire Nano RX](https://www.team-blacksheep.com/products/prod:crossfire_nano_rx?srsltid=AfmBOopvPF1mhPRIS11amSwdKf4OFZlt2ibj7XJwu05kVWt4S_L-ZNuD) (Alternatives: [PX4-Compatible Receivers](../getting_started/rc_transmitter_receiver.md#px4-compatible-receivers-compatible_receivers)).
- Power: 3S Lipo Battery
::: info
The motor driver board requires 3S, but your flight controller might require a different voltage.
To power the flight controller with the same battery you need a Dc-to-DC converter such as the ones listed in [Power Modules & Power Distribution Boards](../power_module/index.md).
(This is not the case in this build, since the flight controller used can be directly supplied by the 3S battery).
:::
- Dc-to-Dc Converter: [BEC12S-PRO](https://www.mateksys.com/?portfolio=bec12s-pro). The servo needs to be supplied with 6-8.4V. Since we are using a 3S battery, we need a Dc-to-Dc converter to transform the voltage into this range (Alternatives: Any other DC-to-DC converter with the correct input/output voltage and current rating higher than 3A).
- GPS: [RTK F9P GPS](https://holybro.com/products/h-rtk-f9p-gnss-series?srsltid=AfmBOoqmsqKx8y60GRVGfWtbcMv_V2m19V4U7-ql9R4NXtrwqzcyXlcF) (Alternatives: [Supported GNSS](../gps_compass/index.md#supported-gnss)).
- I2C Splitter
::: info
This part is only necessary if your flight controller has only one I2C port (we need one for the motor driver board and one for the compass in the gps module).
Many boards will have a dedicated GPS port (which often includes an I2C port) and one or more separate I2C ports for additional peripherals.
:::
- LTE Dongle: Used to establish a data link between the vehicle and the ground control station (There are many alternative ways to achieve this such as the ones listed in [Data Links](../data_links/index.md)).
## Wiring and Assembly
The following images shows the wiring of the various components of this build. Missing are the connections from the motors to the motor controller board.
![Hiwonder Wiring](../../assets/airframes/rover/hiwonder_rovers/hiwonder_wiring_annotated.png)
::: info
This image only serves as an example for the wiring process, with your hardware this can look very different.
Check the documentation of your parts to ensure that you connect to correct pins.
:::
Now connect the battery to the Dc-to-Dc converter to give it power.
To power the servo, connect the red (6-8.4V) and black (GND) wire to the output of the DC-to-Dc converter and the white (PWM) wire to a PWM output of your flight controller.
![Hiwonder Ackermann Servo Wiring](../../assets/airframes/rover/hiwonder_rovers/hiwonder_ackermann_wiring_annotated.png)
With the wiring complete, you can now securely attach your hardware to the chassi.
::: info
For a quick build you could use double sided tape, but for a long term solution we highly recommend 3d printing mounts that you attach to the chassi using the mounting points.
:::
## PX4 Configuration
Use _QGroundControl_ for rover configuration:
1. [Flash the rover build](../config_rover/index.md#flashing-the-rover-build) onto your flight controller with the following adjustments:
Navigate to the `rc.board_sensors` file of your board and add the following lines (for Skynode S this would be in [boards/auterion/fmu-v6s/init/rc.board_sensors](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/init/rc.board_sensors)):
```sh
if param compare HIWONDER_EMM_EN 1
then
hiwonder_emm start
fi
```
Also add the following line to the `rover.px4board` file of your board (for Skynode S this would be in [boards/auterion/fmu-v6s/rover.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/rover.px4board)):
```sh
CONFIG_DRIVERS_HIWONDER_EMM=y
```
2. In the [Basic Configuration](../config/index.md) section, select the [Airframe](../config/airframe.md) tab.
3. Choose **Hiwonder Ackermann** under the **Rover** category (Alternatively you can set the parameter `SYS_AUTOSTART` to `51002`).
Then configure the actuators:
1. Navigate to [Actuators Configuration & Testing](../config/actuators.md) in QGroundControl.
2. Select the Hiwonder EMM driver from the list of _Actuator Outputs_.
Assign the two populated channels of the motor controller board to `Throttle`. The channels are noted on the motor controller board (alternatively randomly assign the channels and use the actuator testing tab to find the correct assignments).
![Motor Setup](../../assets/airframes/rover/hiwonder_rovers/hiwonder_ackermann_motors.png)
3. Now ensure that both motors are spinning in the same direction. If that is not the case check the `Rev Range` box on one of the motors.
4. Arm the rover in [Manual Mode](../flight_modes_rover/manual.md#manual-mode) and use the trottle stick to drive forwards. If the rover drives backwards instead, invert the `Rev Range` checkboxes on **both** motors.
5. To configure the servo motor, assign the populated PWM channel to `Steering`. Set the minimum value to `800`, the maximum to `2200` and the disarm value to `1500`.
![Servo Setup](../../assets/airframes/rover/hiwonder_rovers/hiwonder_ackermann_servo.png)
6. Arm the rover in [Manual Mode](../flight_modes_rover/manual.md#manual-mode) and use the steering stick to move the servo. If the rover steers in the wrong direction check the `Rev Range` checkbox of the servo.
You have now successfully setup your rover and can start testing all [driving modes](../flight_modes_rover/index.md) PX4 has to offer!
@@ -0,0 +1,88 @@
# Hiwonder Mecanum
The [Hiwonder Mecanum](https://www.hiwonder.com/products/large-metal-4wd-vehicle-chassis-green) rover is a bare-bones platform including a chassi, four [mecanum wheels](https://www.hiwonder.com/products/97mm-mecanum-wheel), four [motors with encoders](https://www.hiwonder.com/products/hall-encoder-dc-geared-motor?variant=40451123675223) and a [motor driver board](https://www.hiwonder.com/products/4-channel-encoder-motor-driver).
The chassi offers many mounting points, providing the flexibility to attach your own flight controller, sensors and other payload.
![Hiwonder Mecanum](../../assets/airframes/rover/hiwonder_rovers/hiwonder_mecanum.png)
This documentation illustrates the setup of the rover and the configuration of the actuators.
## Parts List
::: info
The specific hardware used here only serves to examplify the process and can be easily replaced with what you have access to.
Ensure that the parts are compatible, including the ports available on your flight controller, and adapt the wiring to your hardware.
:::
The following parts are used in this build:
- Frame: [Hiwonder Mecanum Chassi](https://www.hiwonder.com/products/large-metal-4wd-vehicle-chassis-green)
- Flight Controller: [Auterion Skynode S](https://auterion.com/product/skynode-s/) (Alternatives: [Flight Controllers](../flight_controller/index.md)).
- Receiver: [TBS Crossfire Nano RX](https://www.team-blacksheep.com/products/prod:crossfire_nano_rx?srsltid=AfmBOopvPF1mhPRIS11amSwdKf4OFZlt2ibj7XJwu05kVWt4S_L-ZNuD) (Alternatives: [PX4-Compatible Receivers](../getting_started/rc_transmitter_receiver.md#px4-compatible-receivers-compatible_receivers)).
- Power: 3S Lipo Battery
::: info
The motor driver board requires 3S, but your flight controller might require a different voltage.
To power the flight controller with the same battery you need a Dc-to-DC converter such as the ones listed in [Power Modules & Power Distribution Boards](../power_module/index.md).
(This is not the case in this build, since the flight controller used can be directly supplied by the 3S battery).
:::
- GPS: [RTK F9P GPS](https://holybro.com/products/h-rtk-f9p-gnss-series?srsltid=AfmBOoqmsqKx8y60GRVGfWtbcMv_V2m19V4U7-ql9R4NXtrwqzcyXlcF) (Alternatives: [Supported GNSS](../gps_compass/index.md#supported-gnss)).
- I2C Splitter
::: info
This part is only necessary if your flight controller has only one I2C port (we need one for the motor driver board and one for the compass in the gps module).
Many boards will have a dedicated GPS port (which often includes an I2C port) and one or more separate I2C ports for additional peripherals.
:::
- LTE Dongle: Used to establish a data link between the vehicle and the ground control station (There are many alternative ways to achieve this such as the ones listed in [Data Links](../data_links/index.md)).
## Wiring and Assembly
The following images shows the wiring of the various components of this build. Missing are the connections from the motors to the motor controller board.
![Hiwonder Wiring](../../assets/airframes/rover/hiwonder_rovers/hiwonder_wiring_annotated.png)
::: info
This image only serves as an example for the wiring process, with your hardware this can look very different.
Check the documentation of your parts to ensure that you connect to correct pins.
:::
To assemble your rover connect the motors to the chassi using the supplied screws, mount the wheels to the motor shafts (there are 2 different types of mecanum wheels, make sure you mount them to the correct motor!) and securely attach your hardware.
::: info
For a quick build you could use double sided tape, but for a long term solution we highly recommend 3d printing mounts that you attach to the chassi using the mounting points.
:::
## PX4 Configuration
Use _QGroundControl_ for rover configuration:
1. [Flash the rover build](../config_rover/index.md#flashing-the-rover-build) onto your flight controller with the following adjustments:
Navigate to the `rc.board_sensors` file of your board and add the following lines (for Skynode S this would be in [boards/auterion/fmu-v6s/init/rc.board_sensors](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/init/rc.board_sensors)):
```sh
if param compare HIWONDER_EMM_EN 1
then
hiwonder_emm start
fi
```
Also add the following line to the `rover.px4board` file of your board (for Skynode S this would be in [boards/auterion/fmu-v6s/rover.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/rover.px4board)):
```sh
CONFIG_DRIVERS_HIWONDER_EMM=y
```
2. In the [Basic Configuration](../config/index.md) section, select the [Airframe](../config/airframe.md) tab.
3. Choose **Hiwonder Mecanum** under the **Rover** category (Alternatively you can set the parameter `SYS_AUTOSTART` to `52001`).
Then configure the actuators:
1. Navigate to [Actuators Configuration & Testing](../config/actuators.md) in QGroundControl.
1. Select the Hiwonder EMM driver from the list of _Actuator Outputs_.
Assign the channels to the corresponding motor. The channels are noted on the motor controller board (alternatively randomly assign the channels and use the actuator testing tab to find the correct assignments).
Now ensure that the motors are all spinning in the same direction. If that is not the case check the `Rev Range` box on the ones that are spinning in the opposite direction.
![Motor Setup](../../assets/airframes/rover/hiwonder_rovers/hiwonder_mecanum_motors.png)
1. Arm the rover in [Manual Mode](../flight_modes_rover/manual.md#manual-mode) and use the trottle stick to drive forwards. If the rover drives backwards instead, invert the `Rev Range` checkboxes on **all** motors.
You have now successfully setup your rover and can start testing all [driving modes](../flight_modes_rover/index.md) PX4 has to offer!
@@ -0,0 +1,88 @@
# Hiwonder Tracked
The [Hiwonder Tracked](https://www.hiwonder.com/products/suspended-shock-absorbing-tracked-chassis?variant=40378709835863) rover is a bare-bones platform including a chassi, two tracks, two [motors with encoders](https://www.hiwonder.com/products/hall-encoder-dc-geared-motor?variant=40451123675223) and a [motor driver board](https://www.hiwonder.com/products/4-channel-encoder-motor-driver).
The chassi offers many mounting points, providing the flexibility to attach your own flight controller, sensors and other payload.
![Hiwonder Tracked](../../assets/airframes/rover/hiwonder_rovers/hiwonder_tracked.png)
This documentation illustrates the setup of the rover and the configuration of the actuators.
## Parts List
::: info
The specific hardware used here only serves to examplify the process and can be easily replaced with what you have access to.
Ensure that the parts are compatible, including the ports available on your flight controller, and adapt the wiring to your hardware.
:::
The following parts are used in this build:
- Frame: [Hiwonder Tracked Chassi](https://www.hiwonder.com/products/suspended-shock-absorbing-tracked-chassis?variant=40378709835863)
- Flight Controller: [Auterion Skynode S](https://auterion.com/product/skynode-s/) (Alternatives: [Flight Controllers](../flight_controller/index.md)).
- Receiver: [TBS Crossfire Nano RX](https://www.team-blacksheep.com/products/prod:crossfire_nano_rx?srsltid=AfmBOopvPF1mhPRIS11amSwdKf4OFZlt2ibj7XJwu05kVWt4S_L-ZNuD) (Alternatives: [PX4-Compatible Receivers](../getting_started/rc_transmitter_receiver.md#px4-compatible-receivers-compatible_receivers)).
- Power: 3S Lipo Battery
::: info
The motor driver board requires 3S, but your flight controller might require a different voltage.
To power the flight controller with the same battery you need a Dc-to-DC converter such as the ones listed in [Power Modules & Power Distribution Boards](../power_module/index.md).
(This is not the case in this build, since the flight controller used can be directly supplied by the 3S battery).
:::
- GPS: [RTK F9P GPS](https://holybro.com/products/h-rtk-f9p-gnss-series?srsltid=AfmBOoqmsqKx8y60GRVGfWtbcMv_V2m19V4U7-ql9R4NXtrwqzcyXlcF) (Alternatives: [Supported GNSS](../gps_compass/index.md#supported-gnss)).
- I2C Splitter
::: info
This part is only necessary if your flight controller has only one I2C port (we need one for the motor driver board and one for the compass in the gps module).
Many boards will have a dedicated GPS port (which often includes an I2C port) and one or more separate I2C ports for additional peripherals.
:::
- LTE Dongle: Used to establish a data link between the vehicle and the ground control station (There are many alternative ways to achieve this such as the ones listed in [Data Links](../data_links/index.md)).
## Wiring and Assembly
The following images shows the wiring of the various components of this build. Missing are the connections from the motors to the motor controller board.
![Hiwonder Wiring](../../assets/airframes/rover/hiwonder_rovers/hiwonder_wiring_annotated.png)
::: info
This image only serves as an example for the wiring process, with your hardware this can look very different.
Check the documentation of your parts to ensure that you connect to correct pins.
:::
With the wiring complete, you can now securely attach your hardware to the chassi.
::: info
For a quick build you could use double sided tape, but for a long term solution we highly recommend 3d printing mounts that you attach to the chassi using the mounting points.
:::
## PX4 Configuration
Use _QGroundControl_ for rover configuration:
1. [Flash the rover build](../config_rover/index.md#flashing-the-rover-build) onto your flight controller with the following adjustments:
Navigate to the `rc.board_sensors` file of your board and add the following lines (for Skynode S this would be in [boards/auterion/fmu-v6s/init/rc.board_sensors](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/init/rc.board_sensors)):
```sh
if param compare HIWONDER_EMM_EN 1
then
hiwonder_emm start
fi
```
Also add the following line to the `rover.px4board` file of your board (for Skynode S this would be in [boards/auterion/fmu-v6s/rover.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/rover.px4board)):
```sh
CONFIG_DRIVERS_HIWONDER_EMM=y
```
2. In the [Basic Configuration](../config/index.md) section, select the [Airframe](../config/airframe.md) tab.
3. Choose **Hiwonder Tracked** under the **Rover** category (Alternatively you can set the parameter `SYS_AUTOSTART` to `50002`).
Then configure the actuators:
1. Navigate to [Actuators Configuration & Testing](../config/actuators.md) in QGroundControl.
1. Select the Hiwonder EMM driver from the list of _Actuator Outputs_.
Assign one of the populated channels of the motor controller board to the `Left Motor` and one to the `Right Motor`. The channels are noted on the motor controller board (alternatively randomly assign the channels and use the actuator testing tab to find the correct assignments).
Now ensure that both motors are spinning in the same direction. If that is not the case check the `Rev Range` box on one of the motors.
![Motor Setup](../../assets/airframes/rover/hiwonder_rovers/hiwonder_tracked_motors.png)
2. Arm the rover in [Manual Mode](../flight_modes_rover/manual.md#manual-mode) and use the trottle stick to drive forwards. If the rover drives backwards instead, invert the `Rev Range` checkboxes on **both** motors.
You have now successfully setup your rover and can start testing all [driving modes](../flight_modes_rover/index.md) PX4 has to offer!
+10 -2
View File
@@ -1,5 +1,13 @@
# Complete Vehicles (Rover)
This section contains information about fully assembled vehicles that use PX4:
The following guides exemplify the build process for various hardware setups and can be used as reference for your own rover:
1. [Aion Robotics R1 UGV (Differential Rover)](../complete_vehicles_rover/aion_r1.md)
## Ackermann
1. [Hiwonder Ackermann Chassi](../complete_vehicles_rover/hiwonder_ackermann.md)
## Differential
1. [Hiwonder Tracked Chassi](../complete_vehicles_rover/hiwonder_tracked.md)
2. [(Discontinued) Aion Robotics R1 UGV](../complete_vehicles_rover/aion_r1.md)
## Mecanum
1. [Hiwonder Mecanum Chassi](../complete_vehicles_rover/hiwonder_mecanum.md)
+1 -1
View File
@@ -19,7 +19,7 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun
If you observe a steady state error in the yaw setpoint increase the the integrator of the rate controller: [RO_YAW_RATE_I](../advanced_config/parameter_reference.md#RO_YAW_RATE_I) .
:::
The rover is now ready to drive in [Stabilized mode](../flight_modes_rover/manual.md#stabilized-mode) and the configuration can be continued with [velocity tuning](velocity_tuning.md).
The rover is now ready to drive in [Stabilized mode](../flight_modes_rover/manual.md#stabilized-mode) and the configuration can be continued with [speed tuning](speed_tuning.md).
## Attitude Controller Structure (Info Only)
+1 -1
View File
@@ -9,7 +9,7 @@ Successive steps enable [drive modes](../flight_modes_rover/index.md) with more
| 1 | [Basic Setup](basic_setup.md) | [Full manual mode](../flight_modes_rover/manual.md#manual-mode) |
| 2 | [Rate Tuning](rate_tuning.md) | [Manual acro mode](../flight_modes_rover/manual.md#acro-mode) |
| 3 | [Attitude Tuning](attitude_tuning.md) | [Manual stabilized mode](../flight_modes_rover/manual.md#stabilized-mode) |
| 4 | [Velocity Tuning](velocity_tuning.md) | [Manual position mode](../flight_modes_rover/manual.md#manual-mode) |
| 4 | [Speed Tuning](speed_tuning.md) | [Manual position mode](../flight_modes_rover/manual.md#manual-mode) |
| 5 | [Position Tuning](position_tuning.md) | [Auto modes](../flight_modes_rover/auto.md) |
::: warning
+4 -4
View File
@@ -3,7 +3,7 @@
Position tuning is required in order to use [Auto modes](../flight_modes_rover/auto.md).
:::warning
The [velocity tuning](velocity_tuning.md) must've already been completed before this step!
The [speed tuning](speed_tuning.md) must've already been completed before this step!
:::
The position controller is responsible for autonomously guiding the vehicle to a position setpoint.
@@ -41,7 +41,7 @@ To tune the position controller configure the [parameters](../advanced_config/pa
These two parameters have to be tuned as a pair, repeat until you are satisfied with the behaviour.
:::
3. Plot the `adjusted_speed_body_x_setpoint` and `measured_speed_body_x` from the [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md) message over each other.
3. Plot the `adjusted_speed_body_x_setpoint` and `measured_speed_body_x` from the [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) message over each other.
If the tracking of these setpoints is not satisfactory adjust the values for [RO_SPEED_P](../advanced_config/parameter_reference.md#RO_SPEED_P) and [RO_SPEED_I](../advanced_config/parameter_reference.md#RO_SPEED_I).
## Path Following
@@ -79,7 +79,7 @@ The following parameters are used to tune the algorithm:
During any auto navigation task observe the behaviour of the rover and if you are unsatisfied with the path following, there are 2 steps to take:
1. Check if all the setpoints ([rate](rate_tuning.md), [attitude](attitude_tuning.md) and [velocity](velocity_tuning.md)) are properly tracked.
1. Check if all the setpoints ([rate](rate_tuning.md), [attitude](attitude_tuning.md) and [speed](speed_tuning.md)) are properly tracked.
2. Further tune the [path following algorithm](#path-following).
## Ackermann Rover Only
@@ -157,7 +157,7 @@ When targeting a position setpoint this line is constructed from the current pos
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).
It depends on the speed $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!
+5 -4
View File
@@ -22,8 +22,9 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun
If you see no need to limit the yaw rate, set this parameter to the maximum yaw rate the rover can achieve:
1. In [Manual mode](../flight_modes_rover/manual.md#manual-mode) drive the rover at full throttle and with the maximum steering angle.
1. Set the [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) to the maximum possible value, then in [Acro mode](../flight_modes_rover/manual.md#acro-mode) drive the rover at full throttle and with the maximum steering input.
2. Plot the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) and enter the highest observed value for [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM).
Pay attention to the units, in the log the rate is given as $rad/s$, but the parameter has to be set in $deg/s$.
:::
@@ -53,9 +54,9 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun
To tune this parameter:
1. Put the rover in [Acro mode](../flight_modes_rover/manual.md#acro-mode) and hold the throttle stick and the right stick at a few different levels for a couple of seconds each.
1. Disarm the rover and from the flight log plot the `adjusted_yaw_rate_setpoint` and the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) over each other.
1. Increase [RO_YAW_RATE_P](#RO_YAW_RATE_P) if the measured value does not track the setpoint fast enough or decrease it if the measurement overshoots the setpoint by too much.
1. Repeat until you are satisfied with the behaviour.
2. Disarm the rover and from the flight log plot the `adjusted_yaw_rate_setpoint` and the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) over each other.
3. Increase [RO_YAW_RATE_P](#RO_YAW_RATE_P) if the measured value does not track the setpoint fast enough or decrease it if the measurement overshoots the setpoint by too much.
4. Repeat until you are satisfied with the behaviour.
:::
4. [RO_YAW_RATE_I](#RO_YAW_RATE_I) [-]: Integral gain of the closed loop yaw rate controller.
@@ -1,4 +1,4 @@
# Velocity Tuning
# Speed Tuning
:::warning
The [attitude tuning](attitude_tuning.md) must've already been completed before this step!
@@ -6,13 +6,13 @@ The [attitude tuning](attitude_tuning.md) must've already been completed before
::: info
To tune we will be using the manual [Position mode](../flight_modes_rover/manual.md#position-mode).
This mode requires a global position estimate (GPS) and tuning of some parameters that go beyond the velocity controller.
If you use a custom external flight mode that controls velocity but does not require a global position estimate you can ignore the [manual position mode parameters](#manual-position-mode-parameters).
This mode requires a global position estimate (GPS) and tuning of some parameters that go beyond the speed controller.
If you use a custom external flight mode that controls speed but does not require a global position estimate you can ignore the [manual position mode parameters](#manual-position-mode-parameters).
:::
## Speed Parameters
To tune the velocity controller configure the following [parameters](../advanced_config/parameters.md) in QGroundControl:
To tune the speed controller configure the following [parameters](../advanced_config/parameters.md) in QGroundControl:
1. [RO_SPEED_LIM](#RO_SPEED_LIM) [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](../flight_modes_rover/manual.md#position-mode) and set an upper limit for the speed setpoint.
@@ -27,7 +27,7 @@ To tune the velocity controller configure the following [parameters](../advanced
1. Set [RO_SPEED_P](#RO_SPEED_P) and [RO_SPEED_I](#RO_SPEED_I) to zero.
This way the speed is only controlled by the feed-forward term, which makes it easier to tune.
2. Put the rover in [Position mode](../flight_modes_rover/manual.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.
3. Disarm the rover and from the flight log plot the `adjusted_speed_body_x_setpoint` and the `measured_speed_body_x` from the [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md) message over each other.
3. Disarm the rover and from the flight log plot the `adjusted_speed_body_x_setpoint` and the `measured_speed_body_x` from the [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) message over each other.
4. If the actual speed of the rover is higher than the speed setpoint, increase [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED).
If it is the other way around decrease the parameter and repeat until you are satisfied with the setpoint tracking.
@@ -86,15 +86,10 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi
The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md).
## Velocity Controller Structure (Info Only)
## Speed Controller Structure (Info Only)
This section provides additional information for developers and people with experience in control system design.
The velocity vector is defined by the following two values:
1. The absolute speed [$m/s$]
2. The direction (bearing) [$rad$]
The speed controller uses the following structure:
![Rover Speed Controller](../../assets/config/rover/rover_speed_controller.png)
@@ -103,7 +98,7 @@ The feed forward mapping is done by interpolating the speed setpoint from [-[RO_
For ackermann and differential rovers the bearing is aligned with the vehicle yaw. Therefor the bearing is simply sent as a yaw setpoint to the [yaw controller](attitude_tuning.md#attitude-controller-structure-info-only) and the speed setpoint is always defined in body x direction.
For mecanum vehicles, the bearing and yaw are decoupled. The direction is controlled by splitting the velocity vector into one speed component in body x direction and one in body y direction.
For mecanum vehicles, the bearing and yaw are decoupled. The direction is controlled by splitting the speed vector into one speed component in body x direction and one in body y direction.
Both these setpoint are then sent to their own closed loop speed controllers.
## Parameter Overview
+21 -21
View File
@@ -9,7 +9,7 @@ Failure injection is disabled by default, and can be enabled using the [SYS_FAIL
Failure injection still in development.
At time of writing (PX4 v1.14):
- It can only be used in simulation (support for both failure injection in real flight is planned).
- Support may vary by failure type and between simulatiors and real vehicle.
- It requires support in the simulator.
It is supported in Gazebo Classic
- Many failure types are not broadly implemented.
@@ -33,31 +33,31 @@ where:
- _component_:
- Sensors:
- `gyro`: Gyro.
- `accel`: Accelerometer.
- `gyro`: Gyroscope
- `accel`: Accelerometer
- `mag`: Magnetometer
- `baro`: Barometer
- `gps`: GPS
- `gps`: Global navigation satellite system
- `optical_flow`: Optical flow.
- `vio`: Visual inertial odometry.
- `vio`: Visual inertial odometry
- `distance_sensor`: Distance sensor (rangefinder).
- `airspeed`: Airspeed sensor.
- `airspeed`: Airspeed sensor
- Systems:
- `battery`: Battery.
- `motor`: Motor.
- `servo`: Servo.
- `avoidance`: Avoidance.
- `rc_signal`: RC Signal.
- `mavlink_signal`: MAVLink signal (data telemetry).
- `battery`: Battery
- `motor`: Motor
- `servo`: Servo
- `avoidance`: Avoidance
- `rc_signal`: RC Signal
- `mavlink_signal`: MAVLink data telemetry connection
- _failure_type_:
- `ok`: Publish as normal (Disable failure injection).
- `off`: Stop publishing.
- `stuck`: Report same value every time (_could_ indicate a malfunctioning sensor).
- `garbage`: Publish random noise. This looks like reading uninitialized memory.
- `wrong`: Publish invalid values (that still look reasonable/aren't "garbage").
- `slow`: Publish at a reduced rate.
- `delayed`: Publish valid data with a significant delay.
- `intermittent`: Publish intermittently.
- `ok`: Publish as normal (Disable failure injection)
- `off`: Stop publishing
- `stuck`: Constantly report the same value which _can_ happen on a malfunctioning sensor
- `garbage`: Publish random noise. This looks like reading uninitialized memory
- `wrong`: Publish invalid values that still look reasonable/aren't "garbage"
- `slow`: Publish at a reduced rate
- `delayed`: Publish valid data with a significant delay
- `intermittent`: Publish intermittently
- _instance number_ (optional): Instance number of affected sensor.
0 (default) indicates all sensors of specified type.
@@ -65,7 +65,7 @@ where:
To simulate losing RC signal without having to turn off your RC controller:
1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN).
1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE).
1. Enter the following commands on the MAVLink console or SITL _pxh shell_:
```sh
+88 -39
View File
@@ -44,7 +44,7 @@ The following ROS 2 messages and their particular fields and field values are al
In addition to providing heartbeat functionality, `OffboardControlMode` has two other main purposes:
1. Controls the level of the [PX4 control architecture](../flight_stack/controller_diagrams.md) at which offboard setpoints must be injected, and disables the bypassed controllers.
1. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used.
2. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used.
The `OffboardControlMode` message is defined as shown.
@@ -62,6 +62,11 @@ bool thrust_and_torque
bool direct_actuator
```
::: warning
The following list shows the `OffboardControlMode` options for copter, fixed-wing, and VTOL.
For rovers see the [rover section](#rover).
:::
The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on.
The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used.
For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message.
@@ -90,20 +95,93 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding
- Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers.
- Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`)
- All values are interpreted in NED (Nord, East, Down) coordinate system and the units are \[m\], \[m/s\] and \[m/s^2\] for position, velocity and acceleration, respectively.
- All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively.
- [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg)
- The following input combination is supported:
- quaternion `q_d` + thrust setpoint `thrust_body`.
Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\].
Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in `[rad/s]`.
- The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The thrust is in the drone body FRD frame and expressed in normalized \[-1, 1\] values.
- The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame.
The thrust is in the drone body FRD frame and expressed in normalized \[-1, 1\] values.
- [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg)
- The following input combination is supported:
- `roll`, `pitch`, `yaw` and `thrust_body`.
- All the values are in the drone body FRD frame. The rates are in \[rad/s\] while thrust_body is normalized in \[-1, 1\].
- All the values are in the drone body FRD frame.
The rates are in `[rad/s]` while thrust_body is normalized in `[-1, 1]`.
### Rover
Rover modules must set the control mode using `OffboardControlMode` and use the appropriate messages to configure the corresponding setpoints.
The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different:
| Category | Usage | Setpoints |
| ------------------------------------------------------------------- | ----------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| (Recommended) [Rover Setpoints](#rover-setpoints) | General rover control | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md), [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md), [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md), [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md), [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md), [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) |
| [Actuator Setpoints](#actuator-setpoints) | Direct actuator control | [ActuatorMotors](../msg_docs/ActuatorMotors.md), [ActuatorServos](../msg_docs/ActuatorServos.md) |
| (Deprecated) [Trajectory Setpoint](#deprecated-trajectory-setpoint) | General vehicle control | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
#### Rover Setpoints
The rover modules use a hierarchical structure to propagate setpoints:
![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg)
The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!).
With this hierarchy there are clear rules for providing a valid control input:
- Provide a position setpoint **or**
- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering).
All combinations of "left" and "right" setpoints are valid.
The following are all valid setpoint combinations and their respective control flags that must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md) (set all others to _false_).
Additionally, for some combinations we require certain setpoints to be published with `NAN` values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above).
&check; are the relevant setpoints we publish, and &cross; are the setpoint that need to be published with `NAN` values.
| Setpoint Combination | Control Flag | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) | [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) | [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) | [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) | [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) | [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) |
| -------------------- | ----------------- | ------------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------- |
| Position | position | &check; | | | | | |
| Speed + Attitude | velocity | | &check; | | &check; | | |
| Speed + Rate | velocity | | &check; | | &cross; | &check; | |
| Speed + Steering | velocity | | &check; | | &cross; | &cross; | &check; |
| Throttle + Attitude | attitude | | | &check; | &check; | | |
| Throttle + Rate | body_rate | | | &check; | | &check; | |
| Throttle + Steering | thrust_and_torque | | | &check; | | | &check; |
::: info
If you intend to use the rover setpoints, we recommend using the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) instead since it simplifies the publishing of these setpoints.
:::
#### Actuator Setpoints
Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md).
In [OffboardControlMode](../msg_docs/OffboardControlMode.md) set `direct_actuator` to _true_ and all other flags to _false_.
::: info
This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step.
We recommend using [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) and [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) instead for low level control (see [Rover Setpoints](#rover-setpoints)).
:::
#### (Deprecated) Trajectory Setpoint
::: warning
The [Rover Setpoints](#rover-setpoints) are a replacement for the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility.
:::
The rover modules support the _position_, _velocity_ and _yaw_ fields of the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md).
However, only one of the fields is active at a time and is defined by the flags of [OffboardControlMode](../msg_docs/OffboardControlMode.md):
| Control Mode Flag | Active Trajectory Setpoint Field |
| ----------------- | -------------------------------- |
| position | position |
| velocity | velocity |
| attitude | yaw |
::: info
Ackermann rovers do not support the yaw setpoint.
:::
### Generic Vehicle
@@ -116,8 +194,10 @@ The following offboard control modes bypass all internal PX4 control loops and s
- [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg)
- You directly control the motor outputs and/or servo outputs.
- Currently works at lower level than then `control_allocator` module. Do not publish these messages when not in offboard mode.
- All the values normalized in \[-1, 1\]. For outputs that do not support negative values, negative entries map to `NaN`.
- Currently works at lower level than then `control_allocator` module.
Do not publish these messages when not in offboard mode.
- All the values normalized in `[-1, 1]`.
For outputs that do not support negative values, negative entries map to `NaN`.
- `NaN` maps to disarmed.
## MAVLink Messages
@@ -200,38 +280,7 @@ The following MAVLink messages and their particular fields and field values are
### Rover
- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED)
- The following input combinations are supported (in `type_mask`): <!-- https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.cpp#L166-L170 -->
- Position setpoint (only `x`, `y`, `z`)
- Specify the _type_ of the setpoint in `type_mask`:
::: info
The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field.
::
The values are:
- 12288: Loiter setpoint (vehicle stops when close enough to setpoint).
- Velocity setpoint (only `vx`, `vy`, `vz`)
- PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED).
- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT)
- The following input combinations are supported (in `type_mask`): <!-- https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.cpp#L166-L170 -->
- Position setpoint (only `lat_int`, `lon_int`, `alt`)
- Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard).
The values are:
- Following bits not set then normal behaviour.
- 12288: Loiter setpoint (vehicle stops when close enough to setpoint).
- PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL).
- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET)
- The following input combinations are supported:
- Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`).
::: info
Only the yaw setting is actually used/extracted.
:::
Rover does not support a MAVLink offboard API (ROS2 is supported).
## Offboard Parameters
+29
View File
@@ -0,0 +1,29 @@
# Apps & API
The rover modules have been tested and integrated with a subset of the available [Apps & API](../middleware/index.md) methods.
We specifically provide guides for using [ROS 2](../ros2/index.md) to interface a companion computer with PX4 via [uXRCE-DDS](../middleware/uxrce_dds.md).
| Method | Description |
| --------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------- |
| [PX4 ROS 2 Interface](#px4-ros-2-interface) (Recommended) | Register a custom mode and publish [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). |
| [ROS 2 Offboard Control](#ros-2-offboard-control) | Use the PX4 internal [Offboard Mode](../flight_modes/offboard.md) and publish messages defined in [dds_topics.yaml](../middleware/dds_topics.md). |
## PX4 ROS 2 Interface
We recommend the use of the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) which allows you to register a custom drive mode and exposes [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints).
By using these setpoints (instead of the PX4 internal rover setpoints), you are guaranteed to send valid control inputs to your vehicle and the control flags for the setpoints you are using are automatically set for you.
Registering a custom drive mode instead of using [ROS 2 Offboard Control](#ros-2-offboard-control) additionally provides the advantages listed [here](../concept/flight_modes.md#internal-vs-external-modes).
To get familiar with this method, read through the guide for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) where we also provide an example app for rover.
## ROS 2 Offboard Control
[ROS 2 Offboard Control](../ros2/offboard_control.md) uses the PX4 internal [Offboard Mode](../flight_modes/offboard.md).
While you can subscribe/publish to all topics specified in [dds_topics.yaml](../middleware/dds_topics.md), not all rover modules support all of these topics (see [Supported Setpoints](../flight_modes/offboard.md#rover)).
Unlike the [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints) exposed through the [PX4 ROS 2 Interface](#px4-ros-2-interface), there is no guarantee that the published setpoints lead to a valid control input.
In addition, the correct control mode flags must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md).
This requires a deeper understanding of PX4 and the structure of the rover modules.
For general information on setting up offboard mode read through [Offboard Mode](../flight_modes/offboard.md) and then consult [Supported Setpoints](../flight_modes/offboard.md#rover).
+69
View File
@@ -0,0 +1,69 @@
# Developer Guide
This developer guide aims to provide information on the structure and design philosophy of the rover modules to kick-start your development.
The guide is structured into the following sections:
- [Developer Guide](#developer-guide)
- [Module Structure](#module-structure)
- [Control Structure](#control-structure)
- [High Level Structure](#high-level-structure)
- [Code Structure](#code-structure)
- [Testing in Simulation](#testing-in-simulation)
- [Contributing](#contributing)
## Module Structure
The rover modules are structured with a focus on modularity and clearly defined interfaces. This allows a developer to work on a specific area or add a new feature without having to worry about the rest of the codebase.
In the following we will elaborate on this structure on different levels:
### Control Structure
The rover modules use a hierarchical structure in which sepoints can be injected at various level through rover specific uORB messages:
![Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg)
The individual controllers (indicated with green boxes) will subscribe to the setpoint coming from the controller one level above and publish a setpoint to the lower level (setpoints indicated with blue boxes).
The strucutre leads to a cascaded PID controller:
![Rover Position Controller](../../assets/config/rover/rover_position_controller.png)
This cascaded structure is highly modular, we only run the loops that are required to control the highest level setpoint that is provided.
### High Level Structure
Putting the control structure into context of the setpoint generation gives us the full picture of the rover module including its external interfaces:
![High Level Structure](../../assets/airframes/rover/high_level_structure.png)
Important to note, is that the highest setpoint that is provided to the control structure will cause the lower setpoints to be overriden by the controllers.
The highest level setpoint is either provided by PX4 if the vehicle is in a PX4 internal drive mode or injected through the API (DDS Bridge).
### Code Structure
The bulk of the rover related code is located in [src/modules](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules). Each rover type has its own subfolder i.e. [src/modules/rover_ackermann](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_ackermann).
Inside the subfolder you will find the following structure exemplified with the ackermann rover module (some files are excluded here):
| Folder or File Names | Purpose |
| ---------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| RoverAckermann.hpp/cpp | Entry Point for the rover module. Responsible for configuring the module, generating Setpoints if the vehicle is in a PX4 internal drive mode and calling the individual controllers. |
| module.yaml | Definition of parameters specific to the rover type. |
| AckermannDriveModes | Contains implementations of the PX4 internal drive modes. |
| AckermannPosControl | Position Controller: Turns position setpoints into speed and attitude setpoints. |
| AckermannSpeedControl | Speed Controller: Turns speed sepoints into throttle setpoints. |
| AckermannAttControl | Attitude Controller: Turns attitude setpoints into rate setpoints. |
| AckermannRateControl | Rate Controller: Turns rate setpoints into normalized steering setpoints. |
| AckermannActControl | Actuator Controller: Turns normalized steering/throttle setpoints into actuator setpoints. |
Additionally, there is a [src/lib/rover_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/lib/rover_control) library that includes functions and parameter definitions that are shared among the rover modules.
## Testing in Simulation
PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features:
- [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover)
- [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover)
- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover)
![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png)
## Contributing
When adding new features it is important to maintain the interfaces of the [High Level Structure](#high-level-structure).
Before opening a PR test your features/improvements in simulation and ideally also on hardware.
In your PR you should include a concise description of your changes and ideally provide logs, screenshots or videos of your code in action.
+10 -16
View File
@@ -5,16 +5,17 @@
:::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!
Check the [Rover Developer Guide](../frames_rover/developer_guide.md) to kick-start your development!
:::
![Rovers](../../assets/airframes/rover/rovers.png)
![Rovers](../../assets/airframes/rover/hiwonder_rovers/hiwonder_rovers.png)
PX4 provides support for the three most common types of rovers:
| Rover Type | Steering |
| --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [**Ackermann**](#ackermann) | 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. |
| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels at different speeds. |
| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels (or tracks) at different speeds. |
| [**Mecanum**](#mecanum) | Direction is controlled by moving each mecanum wheel individually at different speeds and in different directions. |
The supported frames can be seen in [Airframes Reference > Rover](../airframes/airframe_reference.md#rover).
@@ -26,12 +27,12 @@ The supported frames can be seen in [Airframes Reference > Rover](../airframes/a
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.
![Ackermann rover](../../assets/airframes/rover/hiwonder_rovers/hiwonder_ackermann.png)
::: 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/axial_trail_honcho.png)
## Differential
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
@@ -40,7 +41,7 @@ A differential rover's motion is controlled using a differential drive mechanism
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)
![Tracked Rover](../../assets/airframes/rover/hiwonder_rovers/hiwonder_tracked.png)
::: info
The differential setup also work for rovers with skid or tank steering.
@@ -53,19 +54,12 @@ The differential setup also work for rovers with skid or tank steering.
A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first.
Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place.
![Mecanum rover](../../assets/airframes/rover/rover_mecanum.png)
![Mecanum rover](../../assets/airframes/rover/hiwonder_rovers/hiwonder_mecanum.png)
## See Also
- [Drive Modes](../flight_modes_rover/index.md).
- [Drive Modes](../flight_modes_rover/index.md)
- [Configuration/Tuning](../config_rover/index.md)
- [Apps & API](../flight_modes_rover/api.md)
- [Complete Vehicles](../complete_vehicles_rover/index.md)
## Simulation
[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers:
- [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover)
- [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover)
![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png)
- [Developer Guide](../frames_rover/developer_guide.md)
+6 -1
View File
@@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Simulation
- TBD
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
### Ethernet
@@ -90,6 +93,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Rover
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
### ROS 2
+2 -2
View File
@@ -1,6 +1,6 @@
# ROS 2 Offboard Control Example
The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
The following C++ example shows how to do multicopter position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node.
The example starts sending setpoints, enters offboard mode, arms, ascends to 5 metres, and waits.
While simple, it shows the main principles of how to use offboard control and how to send vehicle commands.
@@ -22,7 +22,7 @@ To subscribe to data coming from nodes that publish in a different frame (for ex
## Trying it out
Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent.
Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the multicopter simulator, install ROS 2, and start the XRCE-DDS Agent.
After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros2/user_guide.md#build-ros-2-workspace) to run the example.
@@ -343,6 +343,7 @@ The following sections provide a list of supported setpoint types:
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
:::tip
The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental).
@@ -354,6 +355,8 @@ You can add your own setpoint types by adding a class that inherits from `px4_ro
<Badge type="warning" text="MC only" />
<Badge type="warning" text="Multicopter only" />
::: info
This setpoint type is currently only supported for multicopters.
:::
@@ -547,6 +550,40 @@ For example to control a quadrotor, you need to set the first 4 motors according
If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo).
:::
#### Rover Setpoints
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
The rover modules use a hierarchical structure to propagate setpoints:
![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg)
::: info
The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (Overriding them!).
With this hierarchy there are clear rules for providing a valid control input:
- Provide a position setpoint, **or**
- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). All combinations of "left" and "right" setpoints are valid.
For ease of use we expose these valid combinations as new SetpointTypes.
:::
The RoverSetpointTypes exposed through the control interface are combinations of these setpoints that lead to a valid control input:
| SetpointType | Position | Speed | Throttle | Attitude | Rate | Steering | Control Flags |
| ----------------------------------------------------------------------------------------------------------------------------------- | -------- | --------- | --------- | --------- | --------- | --------- | ------------------------------------------------------ |
| [RoverPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverPositionSetpointType.html#details) | &check; | (&check;) | (&check;) | (&check;) | (&check;) | (&check;) | Position, Velocity, Attitude, Rate, Control Allocation |
| [RoverSpeedAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedAttitudeSetpointType.html) | | &check; | (&check;) | &check; | (&check;) | (&check;) | Velocity, Attitude, Rate, Control Allocation |
| [RoverSpeedRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedRateSetpointType.html) | | &check; | (&check;) | | &check; | (&check;) | Velocity, Rate, Control Allocation |
| [RoverSpeedSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedSteeringSetpointType.html) | | &check; | (&check;) | | | &check; | Velocity, Control Allocation |
| [RoverThrottleAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleAttitudeSetpointType.html) | | | &check; | &check; | (&check;) | (&check;) | Attitude, Rate, Control Allocation |
| [RoverThrottleRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleRateSetpointType.html) | | | &check; | | &check; | (&check;) | Rate, Control Allocation |
| [RoverThrottleSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleSteeringSetpointType.html) | | | &check; | | | &check; | Control Allocation |
&check; are the setpoints we publish, and (&check;) are generated internally by the PX4 rover modules according to the hierarchy above.
An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpointType` is provided [here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/rover_velocity).
### Controlling a VTOL
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
+28 -26
View File
@@ -50,22 +50,24 @@ This runs both the PX4 SITL instance and the Gazebo client.
The supported vehicles and `make` commands are listed below.
Note that all gazebo make targets have the prefix `gz_`.
| Vehicle | Command | `PX4_SYS_AUTOSTART` |
| ----------------------------------------------------------------------------------------------------------------------------- | ----------------------------------- | ------------------- |
| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 |
| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 |
| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 |
| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 |
| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 |
| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 |
| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 |
| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 |
| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 |
| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 |
| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 |
| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 |
| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 |
| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 |
| Vehicle | Command | `PX4_SYS_AUTOSTART` |
| ----------------------------------------------------------------------------------------------------------------------------- | ------------------------------------- | ------------------- |
| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 |
| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 |
| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 |
| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 |
| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 |
| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 |
| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 |
| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 |
| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 |
| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 |
| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 |
| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 |
| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 |
| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 |
| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 |
All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository.
@@ -164,16 +166,16 @@ PX4_GZ_WORLD=windy make px4_sitl gz_x500
The [supported worlds](../sim_gazebo_gz/worlds.md) are listed below.
| World | Command | Description |
| ----------------- | ---------------------------------- | ----------------------------------------------------------- |
| `default` | `make px4_sitl *` | Empty world (a grey plane) |
| `aruco` | `make px4_sitl *_aruco` | Empty world with aruco marker for testing precision landing |
| `baylands` | `make px4_sitl *_baylands` | Baylands world surrounded by water |
| `lawn` | `make px4_sitl *_lawn` | Lawn world for testing rovers |
| `rover` | `make px4_sitl *_rover` | Rover world (optimised/preferred) |
| `walls` | `make px4_sitl *_walls` | Wall world for testing collision prevention |
| `windy` | `make px4_sitl *_windy` | Empty world with wind enabled |
| `moving_platform` | `make px4_sitl *_moving_platform` | World with moving takeoff / landing platform |
| World | Command | Description |
| ----------------- | --------------------------------- | ----------------------------------------------------------- |
| `default` | `make px4_sitl *` | Empty world (a grey plane) |
| `aruco` | `make px4_sitl *_aruco` | Empty world with aruco marker for testing precision landing |
| `baylands` | `make px4_sitl *_baylands` | Baylands world surrounded by water |
| `lawn` | `make px4_sitl *_lawn` | Lawn world for testing rovers |
| `rover` | `make px4_sitl *_rover` | Rover world (optimised/preferred) |
| `walls` | `make px4_sitl *_walls` | Wall world for testing collision prevention |
| `windy` | `make px4_sitl *_windy` | Empty world with wind enabled |
| `moving_platform` | `make px4_sitl *_moving_platform` | World with moving takeoff / landing platform |
:::warning
Note that if no world is specified, PX4 will use the `default` world.
+11 -1
View File
@@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor
[Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
```sh
make px4_sitl gz_r1_rover
make px4_sitl gz_rover_differential
```
![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png)
@@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann
```
![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png)
### Mecanum Rover
[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default.
```sh
make px4_sitl gz_rover_mecanum
```
![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png)
+1
View File
@@ -19,3 +19,4 @@ int8[16] actuator_saturation # Indicates actuator saturation status.
# Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value.
uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
+1
View File
@@ -12,3 +12,4 @@ bool fd_motor
float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed)
uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
+2
View File
@@ -81,6 +81,8 @@ UavcanEscController::init()
_param_handles[i] = param_find(param_name);
}
_initialized = true;
return res;
}
+4
View File
@@ -69,6 +69,8 @@ public:
int init();
bool initialized() { return _initialized; };
void update_outputs(uint16_t outputs[MAX_ACTUATORS], unsigned total_outputs);
/**
@@ -97,6 +99,8 @@ private:
typedef uavcan::MethodBinder<UavcanEscController *,
void (UavcanEscController::*)(const uavcan::TimerEvent &)> TimerCbBinder;
bool _initialized{};
esc_status_s _esc_status{};
uORB::PublicationMulti<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
+13 -8
View File
@@ -529,10 +529,16 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
// Actuators
#if defined(CONFIG_UAVCAN_OUTPUTS_CONTROLLER)
ret = _esc_controller.init();
int32_t uavcan_enable = -1;
(void)param_get(param_find("UAVCAN_ENABLE"), &uavcan_enable);
if (ret < 0) {
return ret;
if (uavcan_enable > 2) {
ret = _esc_controller.init();
if (ret < 0) {
return ret;
}
}
#endif
@@ -607,10 +613,6 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
_param_opcode_client.setCallback(ExecuteOpcodeCallback(this, &UavcanNode::cb_opcode));
_param_restartnode_client.setCallback(RestartNodeCallback(this, &UavcanNode::cb_restart));
int32_t uavcan_enable = 1;
(void)param_get(param_find("UAVCAN_ENABLE"), &uavcan_enable);
if (uavcan_enable > 1) {
_servers = new UavcanServers(_node, _node_info_retriever);
@@ -1079,7 +1081,10 @@ void UavcanNode::publish_node_statuses()
bool UavcanMixingInterfaceESC::updateOutputs(uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs,
unsigned num_control_groups_updated)
{
_esc_controller.update_outputs(outputs, num_outputs);
if (_esc_controller.initialized()) {
_esc_controller.update_outputs(outputs, num_outputs);
}
return true;
}
+1
View File
@@ -1956,6 +1956,7 @@ void Commander::run()
fd_status.fd_motor = _failure_detector.getStatusFlags().motor;
fd_status.imbalanced_prop_metric = _failure_detector.getImbalancedPropMetric();
fd_status.motor_failure_mask = _failure_detector.getMotorFailures();
fd_status.motor_stop_mask = _failure_detector.getMotorStopMask();
fd_status.timestamp = hrt_absolute_time();
_failure_detector_status_pub.publish(fd_status);
}
@@ -33,4 +33,5 @@
px4_add_library(failure_detector
FailureDetector.cpp
FailureInjector.cpp
)
@@ -42,123 +42,6 @@
using namespace time_literals;
void FailureInjector::update()
{
vehicle_command_s vehicle_command;
while (_vehicle_command_sub.update(&vehicle_command)) {
if (vehicle_command.command != vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE) {
continue;
}
bool handled = false;
bool supported = false;
const int failure_unit = static_cast<int>(vehicle_command.param1 + 0.5f);
const int failure_type = static_cast<int>(vehicle_command.param2 + 0.5f);
const int instance = static_cast<int>(vehicle_command.param3 + 0.5f);
if (failure_unit == vehicle_command_s::FAILURE_UNIT_SYSTEM_MOTOR) {
handled = true;
if (failure_type == vehicle_command_s::FAILURE_TYPE_OK) {
PX4_INFO("CMD_INJECT_FAILURE, motors ok");
supported = false;
// 0 to signal all
if (instance == 0) {
supported = true;
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
PX4_INFO("CMD_INJECT_FAILURE, motor %d ok", i);
_esc_blocked &= ~(1 << i);
_esc_wrong &= ~(1 << i);
}
} else if (instance >= 1 && instance <= esc_status_s::CONNECTED_ESC_MAX) {
supported = true;
PX4_INFO("CMD_INJECT_FAILURE, motor %d ok", instance - 1);
_esc_blocked &= ~(1 << (instance - 1));
_esc_wrong &= ~(1 << (instance - 1));
}
}
else if (failure_type == vehicle_command_s::FAILURE_TYPE_OFF) {
PX4_WARN("CMD_INJECT_FAILURE, motors off");
supported = true;
// 0 to signal all
if (instance == 0) {
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
PX4_INFO("CMD_INJECT_FAILURE, motor %d off", i);
_esc_blocked |= 1 << i;
}
} else if (instance >= 1 && instance <= esc_status_s::CONNECTED_ESC_MAX) {
PX4_INFO("CMD_INJECT_FAILURE, motor %d off", instance - 1);
_esc_blocked |= 1 << (instance - 1);
}
}
else if (failure_type == vehicle_command_s::FAILURE_TYPE_WRONG) {
PX4_INFO("CMD_INJECT_FAILURE, motors wrong");
supported = true;
// 0 to signal all
if (instance == 0) {
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
PX4_INFO("CMD_INJECT_FAILURE, motor %d wrong", i);
_esc_wrong |= 1 << i;
}
} else if (instance >= 1 && instance <= esc_status_s::CONNECTED_ESC_MAX) {
PX4_INFO("CMD_INJECT_FAILURE, motor %d wrong", instance - 1);
_esc_wrong |= 1 << (instance - 1);
}
}
}
if (handled) {
vehicle_command_ack_s ack{};
ack.command = vehicle_command.command;
ack.from_external = false;
ack.result = supported ?
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
ack.timestamp = hrt_absolute_time();
_command_ack_pub.publish(ack);
}
}
}
void FailureInjector::manipulateEscStatus(esc_status_s &status)
{
if (_esc_blocked != 0 || _esc_wrong != 0) {
unsigned offline = 0;
for (int i = 0; i < status.esc_count; i++) {
const unsigned i_esc = status.esc[i].actuator_function - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1;
if (_esc_blocked & (1 << i_esc)) {
unsigned function = status.esc[i].actuator_function;
memset(&status.esc[i], 0, sizeof(status.esc[i]));
status.esc[i].actuator_function = function;
offline |= 1 << i;
} else if (_esc_wrong & (1 << i_esc)) {
// Create wrong rerport for this motor by scaling key values up and down
status.esc[i].esc_voltage *= 0.1f;
status.esc[i].esc_current *= 0.1f;
status.esc[i].esc_rpm *= 10.0f;
}
}
status.esc_online_flags &= ~offline;
}
}
FailureDetector::FailureDetector(ModuleParams *parent) :
ModuleParams(parent)
{
@@ -1,4 +1,3 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
@@ -43,6 +42,8 @@
#pragma once
#include "FailureInjector.hpp"
#include <lib/hysteresis/hysteresis.h>
#include <lib/mathlib/mathlib.h>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
@@ -56,12 +57,9 @@
#include <uORB/topics/sensor_selection.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_imu_status.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/pwm_input.h>
union failure_detector_status_u {
@@ -80,20 +78,6 @@ union failure_detector_status_u {
using uORB::SubscriptionData;
class FailureInjector
{
public:
void update();
void manipulateEscStatus(esc_status_s &status);
private:
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
uint32_t _esc_blocked{};
uint32_t _esc_wrong{};
};
class FailureDetector : public ModuleParams
{
public:
@@ -105,6 +89,7 @@ public:
const decltype(failure_detector_status_u::flags) &getStatusFlags() const { return _status.flags; }
float getImbalancedPropMetric() const { return _imbalanced_prop_lpf.getState(); }
uint16_t getMotorFailures() const { return _motor_failure_esc_timed_out_mask | _motor_failure_esc_under_current_mask; }
uint16_t getMotorStopMask() { return _failure_injector.getMotorStopMask(); }
private:
void updateAttitudeStatus(const vehicle_status_s &vehicle_status);
@@ -0,0 +1,134 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "FailureInjector.hpp"
#include <parameters/param.h>
#include <uORB/topics/actuator_motors.h>
FailureInjector::FailureInjector()
{
int32_t param_sys_failure_en = 0;
if ((param_get(param_find("SYS_FAILURE_EN"), &param_sys_failure_en) == PX4_OK)
&& (param_sys_failure_en == 1)) {
_failure_injection_enabled = true;
}
}
void FailureInjector::update()
{
if (!_failure_injection_enabled) { return; }
vehicle_command_s vehicle_command;
while (_vehicle_command_sub.update(&vehicle_command)) {
const int failure_unit = static_cast<int>(vehicle_command.param1 + 0.5f);
const int failure_type = static_cast<int>(vehicle_command.param2 + 0.5f);
if (vehicle_command.command != vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE
|| failure_unit != vehicle_command_s::FAILURE_UNIT_SYSTEM_MOTOR) {
continue;
}
const int instance = static_cast<int>(vehicle_command.param3 + 0.5f);
bool supported = false;
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
if (instance != 0 && i != (instance - 1)) {
continue;
}
switch (failure_type) {
case vehicle_command_s::FAILURE_TYPE_OK:
supported = true;
PX4_INFO("CMD_INJECT_FAILURE, motor %d ok", i + 1);
_motor_stop_mask &= ~(1 << i);
_esc_telemetry_blocked_mask &= ~(1 << i);
_esc_telemetry_wrong_mask &= ~(1 << i);
break;
case vehicle_command_s::FAILURE_TYPE_OFF:
supported = true;
PX4_INFO("CMD_INJECT_FAILURE, motor %d off", i + 1);
_motor_stop_mask |= 1 << i;
break;
case vehicle_command_s::FAILURE_TYPE_STUCK:
supported = true;
PX4_INFO("CMD_INJECT_FAILURE, motor %d no esc telemetry", i + 1);
_esc_telemetry_blocked_mask |= 1 << i;
break;
case vehicle_command_s::FAILURE_TYPE_WRONG:
supported = true;
PX4_INFO("CMD_INJECT_FAILURE, motor %d esc telemetry wrong", i);
_esc_telemetry_wrong_mask |= 1 << i;
break;
}
}
vehicle_command_ack_s ack{};
ack.command = vehicle_command.command;
ack.from_external = false;
ack.result = supported ?
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
ack.timestamp = hrt_absolute_time();
_command_ack_pub.publish(ack);
}
}
void FailureInjector::manipulateEscStatus(esc_status_s &status)
{
if (!_failure_injection_enabled) { return; }
if (_esc_telemetry_blocked_mask != 0 || _esc_telemetry_wrong_mask != 0) {
for (int i = 0; i < status.esc_count; i++) {
const unsigned i_esc = status.esc[i].actuator_function - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1;
if (_esc_telemetry_blocked_mask & (1 << i_esc)) {
unsigned function = status.esc[i].actuator_function;
memset(&status.esc[i], 0, sizeof(status.esc[i]));
status.esc[i].actuator_function = function;
status.esc_online_flags &= ~(1 << i);
} else if (_esc_telemetry_wrong_mask & (1 << i_esc)) {
// Create wrong rerport for this motor by scaling key values up and down
status.esc[i].esc_voltage *= 0.1f;
status.esc[i].esc_current *= 0.1f;
status.esc[i].esc_rpm *= 10.0f;
}
}
}
}
@@ -0,0 +1,59 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_command.h>
class FailureInjector
{
public:
FailureInjector();
void update();
void manipulateEscStatus(esc_status_s &status);
uint32_t getMotorStopMask() { return _motor_stop_mask; }
private:
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
bool _failure_injection_enabled = false;
uint32_t _motor_stop_mask{};
uint32_t _esc_telemetry_blocked_mask{};
uint32_t _esc_telemetry_wrong_mask{};
};
@@ -641,6 +641,7 @@ ControlAllocator::publish_control_allocator_status(int matrix_index)
// Handled motor failures
control_allocator_status.handled_motor_failure_mask = _handled_motor_failure_bitmask;
control_allocator_status.motor_stop_mask = _motor_stop_mask;
_control_allocator_status_pub[matrix_index].publish(control_allocator_status);
}
@@ -665,7 +666,9 @@ ControlAllocator::publish_actuator_controls()
int actuator_idx = 0;
int actuator_idx_matrix[ActuatorEffectiveness::MAX_NUM_MATRICES] {};
uint32_t stopped_motors = _actuator_effectiveness->getStoppedMotors() | _handled_motor_failure_bitmask;
uint32_t stopped_motors = _actuator_effectiveness->getStoppedMotors()
| _handled_motor_failure_bitmask
| _motor_stop_mask;
// motors
int motors_idx;
@@ -716,8 +719,13 @@ ControlAllocator::check_for_motor_failures()
if ((FailureMode)_param_ca_failure_mode.get() > FailureMode::IGNORE
&& _failure_detector_status_sub.update(&failure_detector_status)) {
if (failure_detector_status.fd_motor) {
if (_motor_stop_mask != failure_detector_status.motor_stop_mask) {
_motor_stop_mask = failure_detector_status.motor_stop_mask;
PX4_WARN("Stopping motors (%d)", _motor_stop_mask);
}
if (failure_detector_status.fd_motor) {
if (_handled_motor_failure_bitmask != failure_detector_status.motor_failure_mask) {
// motor failure bitmask changed
switch ((FailureMode)_param_ca_failure_mode.get()) {
@@ -201,6 +201,7 @@ private:
// Reflects motor failures that are currently handled, not motor failures that are reported.
// For example, the system might report two motor failures, but only the first one is handled by CA
uint16_t _handled_motor_failure_bitmask{0};
uint16_t _motor_stop_mask{0};
perf_counter_t _loop_perf; /**< loop duration performance counter */
@@ -81,6 +81,8 @@ void Ekf::controlGravityFusion(const imuSample &imu)
0.25f); // innovation gate
// update the states and covariance using sequential fusion
bool fused[3] {};
for (uint8_t index = 0; index <= 2; index++) {
// Calculate Kalman gains and observation jacobians
if (index == 0) {
@@ -108,10 +110,16 @@ void Ekf::controlGravityFusion(const imuSample &imu)
const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2];
if (_control_status.flags.gravity_vector && !_aid_src_gravity.innovation_rejected && !accel_clipping) {
measurementUpdate(K, H, _aid_src_gravity.observation_variance[index], _aid_src_gravity.innovation[index]);
fused[index] = measurementUpdate(K, H,
_aid_src_gravity.observation_variance[index], _aid_src_gravity.innovation[index]);
}
}
_aid_src_gravity.fused = true;
_aid_src_gravity.time_last_fuse = imu.time_us;
if (fused[0] && fused[1] && fused[2]) {
_aid_src_gravity.fused = true;
_aid_src_gravity.time_last_fuse = imu.time_us;
} else {
_aid_src_gravity.fused = false;
}
}
@@ -126,9 +126,9 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample)
stopRngHgtFusion();
}
} else {
} else if (starting_conditions_passing) {
if (_params.ekf2_hgt_ref == static_cast<int32_t>(HeightSensor::RANGE)) {
if (do_conditional_range_aid && starting_conditions_passing) {
if (do_conditional_range_aid) {
// Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference.
ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::RANGE;
@@ -141,7 +141,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample)
resetAidSourceStatusZeroInnovation(aid_src);
}
} else if (do_range_aid && starting_conditions_passing) {
} else if (do_range_aid) {
// Range finder is the primary height source, the ground is now the datum used
// to compute the local vertical position
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
@@ -158,12 +158,11 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample)
}
} else {
if ((do_conditional_range_aid || do_range_aid) && starting_conditions_passing) {
if ((do_conditional_range_aid || do_range_aid)) {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
_control_status.flags.rng_hgt = true;
if (!_control_status.flags.opt_flow_terrain && aid_src.innovation_rejected) {
ECL_INFO("starting %s height fusion, resetting terrain", HGT_SRC_NAME);
resetTerrainToRng(aid_src);
resetAidSourceStatusZeroInnovation(aid_src);
}
@@ -174,13 +173,6 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample)
if (_control_status.flags.rng_hgt || _control_status.flags.rng_terrain) {
if (continuing_conditions_passing) {
if (do_conditional_range_aid) {
_height_sensor_ref = HeightSensor::RANGE;
} else if (_height_sensor_ref == HeightSensor::RANGE) {
_height_sensor_ref = HeightSensor::UNKNOWN;
}
if (_range_sensor.isDataHealthy()
&& _control_status.flags.rng_kin_consistent
) {
+3 -3
View File
@@ -44,9 +44,9 @@
#if defined(MODULE_NAME)
#include <px4_platform_common/log.h>
# define ECL_INFO PX4_INFO
# define ECL_WARN PX4_WARN
# define ECL_ERR PX4_ERR
# define ECL_INFO PX4_DEBUG
# define ECL_WARN PX4_DEBUG
# define ECL_ERR PX4_DEBUG
# define ECL_DEBUG PX4_DEBUG
#else
# define ECL_INFO(X, ...) printf(X "\n", ##__VA_ARGS__)
+1 -4
View File
@@ -112,11 +112,8 @@ void Ekf::checkHeightSensorRefFallback()
|| ((fallback_list[i] == HeightSensor::GNSS) && _control_status.flags.gps_hgt)
|| ((fallback_list[i] == HeightSensor::RANGE) && _control_status.flags.rng_hgt)
|| ((fallback_list[i] == HeightSensor::EV) && _control_status.flags.ev_hgt)) {
ECL_INFO("fallback to secondary height reference");
_height_sensor_ref = fallback_list[i];
ECL_WARN("fallback to secondary height reference %d", (int)_height_sensor_ref);
break;
}
}
+5 -5
View File
@@ -1059,12 +1059,12 @@ void EKF2::PublishBaroBias(const hrt_abstime &timestamp)
if (_ekf.aid_src_baro_hgt().timestamp_sample != 0) {
const BiasEstimator::status &status = _ekf.getBaroBiasEstimatorStatus();
//if (fabsf(status.bias - _last_baro_bias_published) > 1e-6f) {
_estimator_baro_bias_pub.publish(fillEstimatorBiasMsg(status, _ekf.aid_src_baro_hgt().timestamp_sample, timestamp,
_device_id_baro));
if (fabsf(status.bias - _last_baro_bias_published) > 1e-6f) {
_estimator_baro_bias_pub.publish(fillEstimatorBiasMsg(status, _ekf.aid_src_baro_hgt().timestamp_sample, timestamp,
_device_id_baro));
_last_baro_bias_published = status.bias;
//}
_last_baro_bias_published = status.bias;
}
}
}
#endif // CONFIG_EKF2_BAROMETER
+2 -2
View File
@@ -171,12 +171,12 @@ void LoggedTopics::add_default_topics()
// EKF multi topics
{
// optionally log all estimator* topics at minimal rate
//const uint16_t kEKFVerboseIntervalMilliseconds = 500; // 2 Hz
const uint16_t kEKFVerboseIntervalMilliseconds = 500; // 2 Hz
const struct orb_metadata *const *topic_list = orb_get_topics();
for (size_t i = 0; i < orb_topics_count(); i++) {
if (strncmp(topic_list[i]->o_name, "estimator", 9) == 0) {
add_topic_multi(topic_list[i]->o_name, 0, 1, false);
add_optional_topic_multi(topic_list[i]->o_name, kEKFVerboseIntervalMilliseconds);
}
}
}
@@ -80,6 +80,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 &&
!(req_list.target_component >= MAV_COMP_ID_CAMERA && req_list.target_component <= MAV_COMP_ID_CAMERA6) &&
(req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
// publish list request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
@@ -139,6 +140,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (set.target_system == mavlink_system.sysid && set.target_component < 127 &&
!(set.target_component >= MAV_COMP_ID_CAMERA && set.target_component <= MAV_COMP_ID_CAMERA6) &&
(set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
@@ -217,6 +219,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 &&
!(req_read.target_component >= MAV_COMP_ID_CAMERA && req_read.target_component <= MAV_COMP_ID_CAMERA6) &&
(req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
+6 -6
View File
@@ -175,12 +175,6 @@ extern "C" __EXPORT int failure_main(int argc, char *argv[])
return 0;
}
if (argc < 3) {
PX4_ERR("Not enough arguments.");
print_usage();
return 1;
}
const char *myoptarg = nullptr;
int ch = 0;
int myoptind = 1;
@@ -200,6 +194,12 @@ extern "C" __EXPORT int failure_main(int argc, char *argv[])
}
}
if ((argc < 3) || (myoptind + 1) >= argc) {
print_usage();
PX4_ERR("Not enough arguments.");
return 1;
}
const char *requested_failure_unit = argv[myoptind];
for (const auto &failure_unit : failure_units) {