Compare commits
7 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 25386c28d5 | |||
| 1b3edcd704 | |||
| 83e1c07e83 | |||
| ffff79b306 | |||
| 8a27b1a253 | |||
| 1ff7657b04 | |||
| 208d90a10c |
@@ -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()
|
||||
|
||||
|
||||
|
Before Width: | Height: | Size: 57 KiB |
|
After Width: | Height: | Size: 171 KiB |
|
After Width: | Height: | Size: 271 KiB |
|
After Width: | Height: | Size: 48 KiB |
|
After Width: | Height: | Size: 74 KiB |
|
After Width: | Height: | Size: 236 KiB |
|
After Width: | Height: | Size: 263 KiB |
|
After Width: | Height: | Size: 57 KiB |
|
After Width: | Height: | Size: 648 KiB |
|
After Width: | Height: | Size: 306 KiB |
|
After Width: | Height: | Size: 46 KiB |
|
After Width: | Height: | Size: 223 KiB |
|
Before Width: | Height: | Size: 53 KiB |
|
Before Width: | Height: | Size: 31 KiB After Width: | Height: | Size: 77 KiB |
|
Before Width: | Height: | Size: 1.6 MiB |
|
Before Width: | Height: | Size: 2.1 MiB After Width: | Height: | Size: 21 KiB |
|
Before Width: | Height: | Size: 2.2 MiB After Width: | Height: | Size: 47 KiB |
|
Before Width: | Height: | Size: 2.1 MiB After Width: | Height: | Size: 14 KiB |
|
Before Width: | Height: | Size: 2.1 MiB After Width: | Height: | Size: 13 KiB |
|
Before Width: | Height: | Size: 18 KiB After Width: | Height: | Size: 67 KiB |
|
Before Width: | Height: | Size: 22 KiB After Width: | Height: | Size: 60 KiB |
|
After Width: | Height: | Size: 64 KiB |
@@ -414,11 +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.
|
||||
|
||||

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

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

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

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

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

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

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

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

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

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

|
||||
|
||||
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!
|
||||
@@ -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)
|
||||
|
||||
@@ -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)
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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!
|
||||
|
||||
@@ -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:
|
||||
|
||||

|
||||
@@ -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
|
||||
@@ -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:
|
||||
|
||||

|
||||
|
||||
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:
|
||||
|
||||

|
||||
|
||||
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:
|
||||
|
||||

|
||||
|
||||
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)
|
||||
|
||||

|
||||
|
||||
## 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.
|
||||
|
||||
@@ -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!
|
||||
:::
|
||||
|
||||

|
||||

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

|
||||
|
||||
::: info
|
||||
PX4 does not require that the vehicle uses the Ackermann geometry and will work with any front-steering rover.
|
||||
:::
|
||||
|
||||

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

|
||||

|
||||
|
||||
::: info
|
||||
The differential setup also work for rovers with skid or tank steering.
|
||||
@@ -53,7 +54,7 @@ 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.
|
||||
|
||||

|
||||

|
||||
|
||||
## See Also
|
||||
|
||||
@@ -61,12 +62,4 @@ Each wheel is driven by its own motor, and by controlling the speed and directio
|
||||
- [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)
|
||||
|
||||

|
||||
- [Developer Guide](../frames_rover/developer_guide.md)
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -91,6 +94,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
|
||||
|
||||
- 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
|
||||
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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
|
||||
```
|
||||
|
||||

|
||||
@@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann
|
||||
```
|
||||
|
||||

|
||||
|
||||
### 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
|
||||
```
|
||||
|
||||

|
||||
|
||||