Skip to content

Commit f4ea6fe

Browse files
committed
Update metadata for modules and params
1 parent 996f9a8 commit f4ea6fe

File tree

4 files changed

+192
-14
lines changed

4 files changed

+192
-14
lines changed

docs/en/advanced_config/parameter_reference.md

Lines changed: 119 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -15107,6 +15107,7 @@ Specify USB MAVLink mode.
1510715107
- `10`: gimbal
1510815108
- `11`: onboard_low_bandwidth
1510915109
- `12`: uavionix
15110+
- `13`: Low Bandwidth
1511015111

1511115112
| Reboot | minValue | maxValue | increment | default | unit |
1511215113
| ------- | -------- | -------- | --------- | ------- | ---- |
@@ -15924,7 +15925,7 @@ the estimated time it takes to reach the RTL destination.
1592415925

1592515926
| Reboot | minValue | maxValue | increment | default | unit |
1592615927
| ------ | -------- | -------- | --------- | ------- | ---- |
15927-
|   | | | 1 | 3 |
15928+
|   | | | 1 | 0 |
1592815929

1592915930
### COM_FLT_PROFILE (`INT32`) {#COM_FLT_PROFILE}
1593015931

@@ -17009,6 +17010,21 @@ Sets the number of standard deviations used by the innovation consistency test.
1700917010
| ------ | -------- | -------- | --------- | ------- | ---- |
1701017011
|   | 1.0 | | | 3.0 | SD |
1701117012

17013+
### EKF2_AGP_MODE (`INT32`) {#EKF2_AGP_MODE}
17014+
17015+
Fusion reset mode.
17016+
17017+
Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available
17018+
17019+
**Values:**
17020+
17021+
- `0`: Automatic
17022+
- `1`: Dead-reckoning
17023+
17024+
| Reboot | minValue | maxValue | increment | default | unit |
17025+
| ------ | -------- | -------- | --------- | ------- | ---- |
17026+
|   | | | | 0 |
17027+
1701217028
### EKF2_AGP_NOISE (`FLOAT`) {#EKF2_AGP_NOISE}
1701317029

1701417030
Measurement noise for aux global position measurements.
@@ -20106,6 +20122,20 @@ Auto-detection will probe all protocols, and thus is a bit slower.
2010620122
| ------- | -------- | -------- | --------- | ------- | ---- |
2010720123
| ✓ | 0 | 6 | | 1 |
2010820124

20125+
### GPS_CFG_WIPE (`INT32`) {#GPS_CFG_WIPE}
20126+
20127+
Wipes the flash config of UBX modules.
20128+
20129+
Some UBX modules have a FLASH that allows to store persistent configuration that will be loaded on start.
20130+
PX4 does override all configuration parameters it needs in RAM, which takes precedence over the values in FLASH.
20131+
However, configuration parameters that are not overriden by PX4 can still cause unexpected problems during flight.
20132+
To avoid these kind of problems a clean config can be reached by wiping the FLASH on boot.
20133+
Note: Currently only supported on UBX.
20134+
20135+
| Reboot | minValue | maxValue | increment | default | unit |
20136+
| ------- | -------- | -------- | --------- | ------------ | ---- |
20137+
| ✓ | | | | Disabled (0) |
20138+
2010920139
### GPS_DUMP_COMM (`INT32`) {#GPS_DUMP_COMM}
2011020140

2011120141
Log GPS communication data.
@@ -24938,11 +24968,13 @@ Acceptance radius for fixedwing altitude.
2493824968

2493924969
Loiter radius (FW only).
2494024970

24941-
Default value of loiter radius in FW mode (e.g. for Loiter mode).
24971+
Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode).
24972+
The direction of the loiter can be set via the sign: A positive value for
24973+
clockwise, negative for counter-clockwise.
2494224974

2494324975
| Reboot | minValue | maxValue | increment | default | unit |
2494424976
| ------ | -------- | -------- | --------- | ------- | ---- |
24945-
|   | 25 | 1000 | 0.5 | 80.0 | m |
24977+
|   | -10000 | 10000 | 0.5 | 80.0 | m |
2494624978

2494724979
### NAV_MC_ALT_RAD (`FLOAT`) {#NAV_MC_ALT_RAD}
2494824980

@@ -26644,6 +26676,48 @@ Can be set to increase the amount of integrator available to counteract disturba
2664426676
| ------ | -------- | -------- | --------- | ------- | ---- |
2664526677
|   | 0.0 | | 0.01 | 0.30 |
2664626678

26679+
## Neural Control
26680+
26681+
### MC_NN_EN (`INT32`) {#MC_NN_EN}
26682+
26683+
If true the neural network control is automatically started on boot.
26684+
26685+
| Reboot | minValue | maxValue | increment | default | unit |
26686+
| ------ | -------- | -------- | --------- | ----------- | ---- |
26687+
|   | | | | Enabled (1) |
26688+
26689+
### MC_NN_MANL_CTRL (`INT32`) {#MC_NN_MANL_CTRL}
26690+
26691+
Enable or disable setting the trajectory setpoint with manual control.
26692+
26693+
| Reboot | minValue | maxValue | increment | default | unit |
26694+
| ------- | -------- | -------- | --------- | ----------- | ---- |
26695+
| ✓ | | | | Enabled (1) |
26696+
26697+
### MC_NN_MAX_RPM (`INT32`) {#MC_NN_MAX_RPM}
26698+
26699+
The maximum RPM of the motors. Used to normalize the output of the neural network.
26700+
26701+
| Reboot | minValue | maxValue | increment | default | unit |
26702+
| ------ | -------- | -------- | --------- | ------- | ---- |
26703+
|   | 0 | 80000 | | 22000 |
26704+
26705+
### MC_NN_MIN_RPM (`INT32`) {#MC_NN_MIN_RPM}
26706+
26707+
The minimum RPM of the motors. Used to normalize the output of the neural network.
26708+
26709+
| Reboot | minValue | maxValue | increment | default | unit |
26710+
| ------ | -------- | -------- | --------- | ------- | ---- |
26711+
|   | 0 | 80000 | | 1000 |
26712+
26713+
### MC_NN_THRST_COEF (`FLOAT`) {#MC_NN_THRST_COEF}
26714+
26715+
Thrust coefficient of the motors. Used to normalize the output of the neural network. Divided by 100 000.
26716+
26717+
| Reboot | minValue | maxValue | increment | default | unit |
26718+
| ------ | -------- | -------- | --------- | ------- | ---- |
26719+
|   | 0.0 | 5.0 | | 1.2 |
26720+
2664726721
## OSD
2664826722

2664926723
### MSP_OSD_CONFIG (`INT32`) {#MSP_OSD_CONFIG}
@@ -26804,14 +26878,6 @@ rel_signal is the relative motor control signal between 0 and 1.
2680426878

2680526879
## Payload Deliverer
2680626880

26807-
### PD_GRIPPER_EN (`INT32`) {#PD_GRIPPER_EN}
26808-
26809-
Enable Gripper actuation in Payload Deliverer.
26810-
26811-
| Reboot | minValue | maxValue | increment | default | unit |
26812-
| ------- | -------- | -------- | --------- | ------------ | ---- |
26813-
| ✓ | | | | Disabled (0) |
26814-
2681526881
### PD_GRIPPER_TO (`FLOAT`) {#PD_GRIPPER_TO}
2681626882

2681726883
Timeout for successful gripper actuation acknowledgement.
@@ -26823,7 +26889,7 @@ this time before considering gripper actuation successful and publish a
2682326889

2682426890
| Reboot | minValue | maxValue | increment | default | unit |
2682526891
| ------ | -------- | -------- | --------- | ------- | ---- |
26826-
|   | 0 | | | 3 | s |
26892+
|   | 0 | | | 1 | s |
2682726893

2682826894
### PD_GRIPPER_TYPE (`INT32`) {#PD_GRIPPER_TYPE}
2682926895

@@ -32137,6 +32203,22 @@ Use SENS_MAG_SIDES instead
3213732203
| ------ | -------- | -------- | --------- | ------- | ---- |
3213832204
|   | | | | 63 |
3213932205

32206+
### ILABS_MODE (`INT32`) {#ILABS_MODE}
32207+
32208+
InertialLabs INS sensor mode configuration.
32209+
32210+
Configures whether the driver outputs only raw sensor output (the default),
32211+
or additionally supplies INS data such as position and velocity estimates.
32212+
32213+
**Values:**
32214+
32215+
- `0`: Sensors Only (default)
32216+
- `1`: INS
32217+
32218+
| Reboot | minValue | maxValue | increment | default | unit |
32219+
| ------ | -------- | -------- | --------- | ------- | ---- |
32220+
|   | | | | 0 |
32221+
3214032222
### IMU_ACCEL_CUTOFF (`FLOAT`) {#IMU_ACCEL_CUTOFF}
3214132223

3214232224
Low pass filter cutoff frequency for accel.
@@ -33308,6 +33390,31 @@ Sets the longest time constant that will be applied to the calculation of GPS po
3330833390
| ------ | -------- | -------- | --------- | ------- | ---- |
3330933391
|   | 1.0 | 100.0 | | 10.0 | s |
3331033392

33393+
### SENS_ILABS_CFG (`INT32`) {#SENS_ILABS_CFG}
33394+
33395+
Serial Configuration for InertialLabs.
33396+
33397+
Configure on which serial port to run InertialLabs.
33398+
33399+
**Values:**
33400+
33401+
- `0`: Disabled
33402+
- `6`: UART 6
33403+
- `101`: TELEM 1
33404+
- `102`: TELEM 2
33405+
- `103`: TELEM 3
33406+
- `104`: TELEM/SERIAL 4
33407+
- `201`: GPS 1
33408+
- `202`: GPS 2
33409+
- `203`: GPS 3
33410+
- `300`: Radio Controller
33411+
- `301`: Wifi Port
33412+
- `401`: EXT2
33413+
33414+
| Reboot | minValue | maxValue | increment | default | unit |
33415+
| ------- | -------- | -------- | --------- | ------- | ---- |
33416+
| ✓ | | | | 0 |
33417+
3331133418
### SENS_IMU_AUTOCAL (`INT32`) {#SENS_IMU_AUTOCAL}
3331233419

3331333420
IMU auto calibration.

docs/en/modules/modules_controller.md

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,30 @@ mc_att_control <command> [arguments...]
186186
status print status info
187187
```
188188

189+
## mc_nn_control
190+
191+
Source: [modules/mc_nn_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_nn_control)
192+
193+
### Description
194+
195+
Multicopter Neural Network Control module.
196+
This module is an end-to-end neural network control system for multicopters.
197+
It takes in 15 input values and outputs 4 control actions.
198+
Inputs: [pos_err(3), att(6), vel(3), ang_vel(3)]
199+
Outputs: [Actuator motors(4)]
200+
201+
### Usage {#mc_nn_control_usage}
202+
203+
```
204+
mc_nn_control <command> [arguments...]
205+
Commands:
206+
start
207+
208+
stop
209+
210+
status print status info
211+
```
212+
189213
## mc_pos_control
190214

191215
Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_pos_control)

docs/en/modules/modules_driver_ins.md

Lines changed: 48 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,54 @@
11
# Modules Reference: Ins (Driver)
22

3+
## ilabs
4+
5+
Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs)
6+
7+
### Description
8+
9+
Serial bus driver for the ILabs sensors.
10+
11+
Most boards are configured to enable/start the driver on a specified UART using the SENS_ILABS_CFG.
12+
After that you can use the ILABS_MODE parameter to config outputs:
13+
14+
- Only raw sensor output (the default).
15+
- Sensor output and INS data such as position and velocity estimates.
16+
17+
Setup/usage information: https://docs.px4.io/main/en/sensor/ilabs.html
18+
19+
### Examples
20+
21+
Attempt to start driver on a specified serial device.
22+
23+
```
24+
ilabs start -d /dev/ttyS1
25+
```
26+
27+
Stop driver
28+
29+
```
30+
ilabs stop
31+
```
32+
33+
### Usage {#ilabs_usage}
34+
35+
```
36+
ilabs <command> [arguments...]
37+
Commands:
38+
start Start driver
39+
-d <val> Serial device
40+
41+
status Driver status
42+
43+
stop Stop driver
44+
45+
status Print driver status
46+
```
47+
348
## vectornav
449

550
Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav)
651

7-
852
### Description
953

1054
Serial bus driver for the VectorNav VN-100, VN-200, VN-300.
@@ -16,10 +60,13 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html
1660
### Examples
1761

1862
Attempt to start driver on a specified serial device.
63+
1964
```
2065
vectornav start -d /dev/ttyS1
2166
```
67+
2268
Stop driver
69+
2370
```
2471
vectornav stop
2572
```

docs/en/modules/modules_system.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,7 @@ commander <command> [arguments...]
146146
147147
pair
148148
149-
lockdown
149+
termination
150150
on|off Turn lockdown on or off
151151
152152
set_ekf_origin

0 commit comments

Comments
 (0)