This is a complete list of the parameters which can be set (e.g. via the MAVLink protocol) to control vehicle behaviour. They are stored in persistent storage on the vehicle.
This list is automatically generated from the latest ardupilot source code, and so may contain parameters which are not yet in the stable released versions of the code.
AntennaTracker Parameters
SYSID_THISMAV: MAVLink system ID of this vehicle
Note: This parameter is for advanced users
Allows setting an individual system id for this vehicle to distinguish it from others on the same network
SYSID_MYGCS: Ground station MAVLink system ID
Note: This parameter is for advanced users
The identifier of the ground station in the MAVLink protocol. Don’t change this unless you also modify the ground station to match.
SYSID_TARGET: Target vehicle’s MAVLink system ID
Note: This parameter is for advanced users
The identifier of the vehicle being tracked. This should be zero (to auto detect) or be the same as the SYSID_THISMAV parameter of the vehicle being tracked.
MAG_ENABLE: Enable Compass
Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
YAW_SLEW_TIME: Time for yaw to slew through its full range
This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
Range |
Increment |
Units |
0 - 20 |
0.1 |
seconds |
PITCH_SLEW_TIME: Time for pitch to slew through its full range
This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
Range |
Increment |
Units |
0 - 20 |
0.1 |
seconds |
SCAN_SPEED: Speed at which to rotate in scan mode
This controls how rapidly the tracker will move the servos in SCAN mode
Range |
Increment |
Units |
0 - 100 |
1 |
degrees per second |
MIN_REVERSE_TIME: Minimum time to apply a yaw reversal
When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.
Range |
Increment |
Units |
0 - 20 |
1 |
seconds |
START_LATITUDE: Initial Latitude before GPS lock
Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
Range |
Increment |
Units |
-90 - 90 |
0.000001 |
degrees |
START_LONGITUDE: Initial Longitude before GPS lock
Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
Range |
Increment |
Units |
-180 - 180 |
0.000001 |
degrees |
STARTUP_DELAY: Delay before first servo movement from trim
This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types
Range |
Increment |
Units |
0 - 10 |
0.1 |
seconds |
SERVO_PITCH_TYPE: Type of servo system being used for pitch
This allows selection of position servos or on/off servos for pitch
Values |
Value |
Meaning |
0 |
Position |
1 |
OnOff |
2 |
ContinuousRotation |
|
SERVO_YAW_TYPE: Type of servo system being used for yaw
This allows selection of position servos or on/off servos for yaw
Values |
Value |
Meaning |
0 |
Position |
1 |
OnOff |
2 |
ContinuousRotation |
|
ONOFF_YAW_RATE: Yaw rate for on/off servos
Rate of change of yaw in degrees/second for on/off servos
Range |
Increment |
Units |
0 - 50 |
0.1 |
degrees per second |
ONOFF_PITCH_RATE: Pitch rate for on/off servos
Rate of change of pitch in degrees/second for on/off servos
Range |
Increment |
Units |
0 - 50 |
0.1 |
degrees per second |
ONOFF_YAW_MINT: Yaw minimum movement time
Minimum amount of time in seconds to move in yaw
Range |
Increment |
Units |
0 - 2 |
0.01 |
seconds |
ONOFF_PITCH_MINT: Pitch minimum movement time
Minimim amount of time in seconds to move in pitch
Range |
Increment |
Units |
0 - 2 |
0.01 |
seconds |
YAW_TRIM: Yaw trim
Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.
Range |
Increment |
Units |
-10 - 10 |
0.1 |
degrees |
PITCH_TRIM: Pitch trim
Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.
Range |
Increment |
Units |
-10 - 10 |
0.1 |
degrees |
YAW_RANGE: Yaw Angle Range
Yaw axis total range of motion in degrees
Range |
Increment |
Units |
0 - 360 |
0.1 |
degrees |
DISTANCE_MIN: Distance minimum to target
Tracker will track targets at least this distance away
Range |
Increment |
Units |
0 - 100 |
1 |
meters |
ALT_SOURCE: Altitude Source
What provides altitude information for vehicle. Vehicle only assumes tracker has same altitude as vehicle’s home
Values |
Value |
Meaning |
0 |
Barometer |
1 |
GPS |
2 |
GPS vehicle only |
|
MAV_UPDATE_RATE: Mavlink Update Rate
The rate at which Mavlink updates position and baro data
Range |
Increment |
Units |
1 - 10 |
1 |
hertz |
PITCH_MIN: Minimum Pitch Angle
The lowest angle the pitch can reach
Range |
Increment |
Units |
-90 - 0 |
1 |
degrees |
PITCH_MAX: Maximum Pitch Angle
The highest angle the pitch can reach
Range |
Increment |
Units |
0 - 90 |
1 |
degrees |
LOG_BITMASK: Log bitmask
4 byte bitmap of log types to enable
Bitmask |
Values |
Bit |
Meaning |
0 |
ATTITUDE |
1 |
GPS |
2 |
RCIN |
3 |
IMU |
4 |
RCOUT |
5 |
COMPASS |
6 |
Battery |
|
Value |
Meaning |
127 |
Default |
0 |
Disabled |
|
PITCH2SRV_P: Pitch axis controller P gain
Pitch axis controller P gain. Converts the difference between desired pitch angle and actual pitch angle into a pitch servo pwm change
Range |
Increment |
0.0 - 3.0 |
0.01 |
PITCH2SRV_I: Pitch axis controller I gain
Pitch axis controller I gain. Corrects long-term difference in desired pitch angle vs actual pitch angle
Range |
Increment |
0.0 - 3.0 |
0.01 |
PITCH2SRV_IMAX: Pitch axis controller I gain maximum
Pitch axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
Range |
Increment |
Units |
0 - 4000 |
10 |
decipercent |
PITCH2SRV_D: Pitch axis controller D gain
Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle
Range |
Increment |
0.001 - 0.1 |
0.001 |
YAW2SRV_P: Yaw axis controller P gain
Yaw axis controller P gain. Converts the difference between desired yaw angle (heading) and actual yaw angle into a yaw servo pwm change
Range |
Increment |
0.0 - 3.0 |
0.01 |
YAW2SRV_I: Yaw axis controller I gain
Yaw axis controller I gain. Corrects long-term difference in desired yaw angle (heading) vs actual yaw angle
Range |
Increment |
0.0 - 3.0 |
0.01 |
YAW2SRV_IMAX: Yaw axis controller I gain maximum
Yaw axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
Range |
Increment |
Units |
0 - 4000 |
10 |
decipercent |
YAW2SRV_D: Yaw axis controller D gain
Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle
Range |
Increment |
0.001 - 0.1 |
0.001 |
CMD_TOTAL: Number of loaded mission items
Note: This parameter is for advanced users
Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
BATT2_ Parameters
BATT2_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT2_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT2_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT2_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT2_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT2_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT2_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT2_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT2_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT2_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT2_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT2_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT2_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT2_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT2_FS_LOW_ACT parameter.
BATT2_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT2_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT2_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT2_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT2_FS_CRT_ACT parameter.
BATT2_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT2__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT2_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT2_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT2_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT2_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT2__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT3_ Parameters
BATT3_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT3_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT3_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT3_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT3_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT3_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT3_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT3_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT3_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT3_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT3_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT3_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT3_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT3_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT3_FS_LOW_ACT parameter.
BATT3_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT3_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT3_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT3_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT3_FS_CRT_ACT parameter.
BATT3_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT3__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT3_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT3_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT3_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT3_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT3__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT4_ Parameters
BATT4_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT4_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT4_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT4_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT4_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT4_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT4_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT4_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT4_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT4_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT4_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT4_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT4_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT4_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT4_FS_LOW_ACT parameter.
BATT4_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT4_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT4_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT4_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT4_FS_CRT_ACT parameter.
BATT4_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT4__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT4_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT4_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT4_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT4_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT4__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT5_ Parameters
BATT5_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT5_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT5_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT5_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT5_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT5_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT5_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT5_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT5_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT5_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT5_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT5_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT5_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT5_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT5_FS_LOW_ACT parameter.
BATT5_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT5_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT5_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT5_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT5_FS_CRT_ACT parameter.
BATT5_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT5__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT5_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT5_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT5_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT5_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT5__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT6_ Parameters
BATT6_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT6_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT6_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT6_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT6_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT6_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT6_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT6_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT6_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT6_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT6_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT6_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT6_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
BATT6_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT6_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_CRT_ACT parameter.
BATT6_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT6_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT6_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT6_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT6_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT6__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT7_ Parameters
BATT7_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT7_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT7_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT7_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT7_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT7_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT7_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT7_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT7_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT7_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT7_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT7_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT7_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
BATT7_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT7_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_CRT_ACT parameter.
BATT7_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT7_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT7_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT7_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT7_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT7__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT8_ Parameters
BATT8_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT8_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT8_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT8_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT8_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT8_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT8_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT8_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT8_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT8_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT8_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT8_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT8_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
BATT8_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT8_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_CRT_ACT parameter.
BATT8_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT8_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT8_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT8_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT8_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT8__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT9_ Parameters
BATT9_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT9_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT9_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT9_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT9_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT9_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT9_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT9_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT9_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT9_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT9_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT9_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT9_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
BATT9_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT9_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_CRT_ACT parameter.
BATT9_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT9_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT9_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT9_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT9_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT9__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT_ Parameters
BATT_MONITOR: Battery monitoring
Controls enabling monitoring of the battery’s voltage and current
Values |
RebootRequired |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Maxell |
8 |
UAVCAN-BatteryInfo |
9 |
BLHeli ESC |
10 |
SumOfFollowing |
|
True |
BATT_VOLT_PIN: Battery Voltage sensing pin
Sets the analog input pin that should be used for voltage monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 |
Pixhawk2_PM2 |
100 |
PX4-v1 |
|
True |
BATT_CURR_PIN: Battery Current sensing pin
Sets the analog input pin that should be used for current monitoring.
Values |
RebootRequired |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
14 |
Pixhawk2_PM2 |
101 |
PX4-v1 |
|
True |
BATT_VOLT_MULT: Voltage Multiplier
Note: This parameter is for advanced users
Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery’s voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT_AMP_PERVLT: Amps per volt
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
BATT_AMP_OFFSET: AMP offset
Voltage offset at zero current on current sensor
BATT_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
BATT_WATT_MAX: Maximum allowed power (Watts)
Note: This parameter is for advanced users
If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.
BATT_SERIAL_NUM: Battery serial number
Note: This parameter is for advanced users
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
BATT_LOW_TIMER: Low voltage timeout
Note: This parameter is for advanced users
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Range |
Increment |
Units |
0 - 120 |
1 |
seconds |
BATT_FS_VOLTSRC: Failsafe voltage source
Note: This parameter is for advanced users
Voltage type used for detection of low voltage event
Values |
Value |
Meaning |
0 |
Raw Voltage |
1 |
Sag Compensated Voltage |
|
BATT_LOW_VOLT: Low battery voltage
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
BATT_LOW_MAH: Low battery capacity
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT_CRT_VOLT: Critical battery voltage
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_CRT_ACT parameter.
BATT_CRT_MAH: Battery critical capacity
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT__FS_CRT_ACT parameter.
Increment |
Units |
50 |
milliampere hour |
BATT_FS_LOW_ACT: Low battery failsafe action
What action the vehicle should perform if it hits a low battery failsafe
BATT_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
BATT_ARM_VOLT: Required arming voltage
Note: This parameter is for advanced users
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
BATT_ARM_MAH: Required arming remaining capacity
Note: This parameter is for advanced users
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT__ARM_VOLT parameter.
Increment |
Units |
50 |
milliampere hour |
COMPASS_ Parameters
COMPASS_OFS_X: Compass offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to the compass x-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS_Y: Compass offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to the compass y-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS_Z: Compass offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to the compass z-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_DEC: Compass declination
An angle to compensate between the true north and magnetic north
Range |
Increment |
Units |
-3.142 - 3.142 |
0.01 |
radians |
COMPASS_LEARN: Learn compass offsets automatically
Note: This parameter is for advanced users
Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Internal-Learning |
2 |
EKF-Learning |
3 |
InFlight-Learning |
|
COMPASS_USE: Use compass for yaw
Note: This parameter is for advanced users
Enable or disable the use of the compass (instead of the GPS) for determining heading
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_AUTODEC: Auto Declination
Note: This parameter is for advanced users
Enable or disable the automatic calculation of the declination based on gps location
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_MOTCT: Motor interference compensation type
Note: This parameter is for advanced users
Set motor interference compensation type to disabled, throttle or current. Do not change manually.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Use Throttle |
2 |
Use Current |
|
COMPASS_MOT_X: Motor interference compensation for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT_Y: Motor interference compensation for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT_Z: Motor interference compensation for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_ORIENT: Compass orientation
Note: This parameter is for advanced users
The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
|
COMPASS_EXTERNAL: Compass is attached via an external cable
Note: This parameter is for advanced users
Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_OFS2_X: Compass2 offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to compass2’s x-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS2_Y: Compass2 offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to compass2’s y-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS2_Z: Compass2 offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to compass2’s z-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_MOT2_X: Motor interference compensation to compass2 for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT2_Y: Motor interference compensation to compass2 for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT2_Z: Motor interference compensation to compass2 for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_PRIMARY: Choose primary compass
Note: This parameter is for advanced users
If more than one compass is available, this selects which compass is the primary. When external compasses are connected, they will be ordered first. NOTE: If no external compass is attached, this parameter is ignored.
Values |
Value |
Meaning |
0 |
FirstCompass |
1 |
SecondCompass |
2 |
ThirdCompass |
|
COMPASS_OFS3_X: Compass3 offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to compass3’s x-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS3_Y: Compass3 offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to compass3’s y-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_OFS3_Z: Compass3 offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to compass3’s z-axis values to compensate for metal in the frame
Range |
Increment |
Units |
-400 - 400 |
1 |
milligauss |
COMPASS_MOT3_X: Motor interference compensation to compass3 for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT3_Y: Motor interference compensation to compass3 for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_MOT3_Z: Motor interference compensation to compass3 for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Range |
Increment |
Units |
-1000 - 1000 |
1 |
milligauss per ampere |
COMPASS_DEV_ID: Compass device id
Note: This parameter is for advanced users
Compass device id. Automatically detected, do not set manually
COMPASS_DEV_ID2: Compass2 device id
Note: This parameter is for advanced users
Second compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID3: Compass3 device id
Note: This parameter is for advanced users
Third compass’s device id. Automatically detected, do not set manually
COMPASS_USE2: Compass2 used for yaw
Note: This parameter is for advanced users
Enable or disable the second compass for determining heading.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_ORIENT2: Compass2 orientation
Note: This parameter is for advanced users
The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
|
COMPASS_EXTERN2: Compass2 is attached via an external cable
Note: This parameter is for advanced users
Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_USE3: Compass3 used for yaw
Note: This parameter is for advanced users
Enable or disable the third compass for determining heading.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_ORIENT3: Compass3 orientation
Note: This parameter is for advanced users
The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
|
COMPASS_EXTERN3: Compass3 is attached via an external cable
Note: This parameter is for advanced users
Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_DIA_X: Compass soft-iron diagonal X component
Note: This parameter is for advanced users
DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA_Y: Compass soft-iron diagonal Y component
Note: This parameter is for advanced users
DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA_Z: Compass soft-iron diagonal Z component
Note: This parameter is for advanced users
DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI_X: Compass soft-iron off-diagonal X component
Note: This parameter is for advanced users
ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI_Y: Compass soft-iron off-diagonal Y component
Note: This parameter is for advanced users
ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI_Z: Compass soft-iron off-diagonal Z component
Note: This parameter is for advanced users
ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA2_X: Compass2 soft-iron diagonal X component
Note: This parameter is for advanced users
DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA2_Y: Compass2 soft-iron diagonal Y component
Note: This parameter is for advanced users
DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA2_Z: Compass2 soft-iron diagonal Z component
Note: This parameter is for advanced users
DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI2_X: Compass2 soft-iron off-diagonal X component
Note: This parameter is for advanced users
ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI2_Y: Compass2 soft-iron off-diagonal Y component
Note: This parameter is for advanced users
ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI2_Z: Compass2 soft-iron off-diagonal Z component
Note: This parameter is for advanced users
ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA3_X: Compass3 soft-iron diagonal X component
Note: This parameter is for advanced users
DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA3_Y: Compass3 soft-iron diagonal Y component
Note: This parameter is for advanced users
DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA3_Z: Compass3 soft-iron diagonal Z component
Note: This parameter is for advanced users
DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI3_X: Compass3 soft-iron off-diagonal X component
Note: This parameter is for advanced users
ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI3_Y: Compass3 soft-iron off-diagonal Y component
Note: This parameter is for advanced users
ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI3_Z: Compass3 soft-iron off-diagonal Z component
Note: This parameter is for advanced users
ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_CAL_FIT: Compass calibration fitness
Note: This parameter is for advanced users
This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
Range |
Values |
Increment |
4 - 32 |
Value |
Meaning |
4 |
Very Strict |
8 |
Strict |
16 |
Default |
32 |
Relaxed |
|
0.1 |
COMPASS_OFFS_MAX: Compass maximum offset
Note: This parameter is for advanced users
This sets the maximum allowed compass offset in calibration and arming checks
Range |
Increment |
500 - 3000 |
1 |
COMPASS_TYPEMASK: Compass disable driver type mask
Note: This parameter is for advanced users
This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
Bitmask |
Bit |
Meaning |
0 |
HMC5883 |
1 |
LSM303D |
2 |
AK8963 |
3 |
BMM150 |
4 |
LSM9DS1 |
5 |
LIS3MDL |
6 |
AK09916 |
7 |
IST8310 |
8 |
ICM20948 |
9 |
MMC3416 |
11 |
UAVCAN |
12 |
QMC5883 |
14 |
MAG3110 |
15 |
IST8308 |
|
COMPASS_FLTR_RNG: Range in which sample is accepted
This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
Range |
Increment |
Units |
0 - 100 |
1 |
percent |
COMPASS_AUTO_ROT: Automatically check orientation
When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
CheckOnly |
2 |
CheckAndFix |
|
COMPASS_EXP_DID: Compass device id expected
Note: This parameter is for advanced users
The expected value of COMPASS_DEV_ID, used by arming checks. Setting this to -1 means “don’t care.”
COMPASS_EXP_DID2: Compass2 device id expected
Note: This parameter is for advanced users
The expected value of COMPASS_DEV_ID2, used by arming checks. Setting this to -1 means “don’t care.”
COMPASS_EXP_DID3: Compass3 device id expected
Note: This parameter is for advanced users
The expected value of COMPASS_DEV_ID3, used by arming checks. Setting this to -1 means “don’t care.”
GPS_ Parameters
GPS_TYPE: GPS type
Note: This parameter is for advanced users
GPS type
Values |
RebootRequired |
Value |
Meaning |
0 |
None |
1 |
AUTO |
2 |
uBlox |
3 |
MTK |
4 |
MTK19 |
5 |
NMEA |
6 |
SiRF |
7 |
HIL |
8 |
SwiftNav |
9 |
UAVCAN |
10 |
SBF |
11 |
GSOF |
13 |
ERB |
14 |
MAV |
15 |
NOVA |
|
True |
GPS_TYPE2: 2nd GPS type
Note: This parameter is for advanced users
GPS type of 2nd GPS
Values |
RebootRequired |
Value |
Meaning |
0 |
None |
1 |
AUTO |
2 |
uBlox |
3 |
MTK |
4 |
MTK19 |
5 |
NMEA |
6 |
SiRF |
7 |
HIL |
8 |
SwiftNav |
9 |
UAVCAN |
10 |
SBF |
11 |
GSOF |
13 |
ERB |
14 |
MAV |
15 |
NOVA |
|
True |
GPS_NAVFILTER: Navigation filter setting
Note: This parameter is for advanced users
Navigation filter engine setting
Values |
Value |
Meaning |
0 |
Portable |
2 |
Stationary |
3 |
Pedestrian |
4 |
Automotive |
5 |
Sea |
6 |
Airborne1G |
7 |
Airborne2G |
8 |
Airborne4G |
|
GPS_AUTO_SWITCH: Automatic Switchover Setting
Note: This parameter is for advanced users
Automatic switchover to GPS reporting best lock
Values |
Value |
Meaning |
0 |
Disabled |
1 |
UseBest |
2 |
Blend |
3 |
UseSecond |
|
GPS_MIN_DGPS: Minimum Lock Type Accepted for DGPS
Note: This parameter is for advanced users
Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
Values |
RebootRequired |
Value |
Meaning |
0 |
Any |
50 |
FloatRTK |
100 |
IntegerRTK |
|
True |
GPS_SBAS_MODE: SBAS Mode
Note: This parameter is for advanced users
This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
NoChange |
|
GPS_MIN_ELEV: Minimum elevation
Note: This parameter is for advanced users
This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
Range |
Units |
-100 - 90 |
degrees |
GPS_INJECT_TO: Destination for GPS_INJECT_DATA MAVLink packets
Note: This parameter is for advanced users
The GGS can send raw serial packets to inject data to multiple GPSes.
Values |
Value |
Meaning |
0 |
send to first GPS |
1 |
send to 2nd GPS |
127 |
send to all |
|
GPS_SBP_LOGMASK: Swift Binary Protocol Logging Mask
Note: This parameter is for advanced users
Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
Values |
Value |
Meaning |
0 |
None (0x0000) |
-1 |
All (0xFFFF) |
-256 |
External only (0xFF00) |
|
GPS_RAW_DATA: Raw data logging
Note: This parameter is for advanced users
Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into dataflash log; on Septentrio this will log on the equipment’s SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
Values |
RebootRequired |
Value |
Meaning |
0 |
Ignore |
1 |
Always log |
2 |
Stop logging when disarmed (SBF only) |
5 |
Only log every five samples (uBlox only) |
|
True |
GPS_GNSS_MODE: GNSS system configuration
Note: This parameter is for advanced users
Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
Bitmask |
Values |
Bit |
Meaning |
0 |
GPS |
1 |
SBAS |
2 |
Galileo |
3 |
Beidou |
4 |
IMES |
5 |
QZSS |
6 |
GLOSNASS |
|
Value |
Meaning |
0 |
Leave as currently configured |
1 |
GPS-NoSBAS |
3 |
GPS+SBAS |
4 |
Galileo-NoSBAS |
6 |
Galileo+SBAS |
8 |
Beidou |
51 |
GPS+IMES+QZSS+SBAS (Japan Only) |
64 |
GLONASS |
66 |
GLONASS+SBAS |
67 |
GPS+GLONASS+SBAS |
|
GPS_SAVE_CFG: Save GPS configuration
Note: This parameter is for advanced users
Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
Values |
Value |
Meaning |
0 |
Do not save config |
1 |
Save config |
2 |
Save only when needed |
|
GPS_GNSS_MODE2: GNSS system configuration
Note: This parameter is for advanced users
Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
Bitmask |
Values |
Bit |
Meaning |
0 |
GPS |
1 |
SBAS |
2 |
Galileo |
3 |
Beidou |
4 |
IMES |
5 |
QZSS |
6 |
GLOSNASS |
|
Value |
Meaning |
0 |
Leave as currently configured |
1 |
GPS-NoSBAS |
3 |
GPS+SBAS |
4 |
Galileo-NoSBAS |
6 |
Galileo+SBAS |
8 |
Beidou |
51 |
GPS+IMES+QZSS+SBAS (Japan Only) |
64 |
GLONASS |
66 |
GLONASS+SBAS |
67 |
GPS+GLONASS+SBAS |
|
GPS_AUTO_CONFIG: Automatic GPS configuration
Note: This parameter is for advanced users
Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
Values |
Value |
Meaning |
0 |
Disables automatic configuration |
1 |
Enable automatic configuration |
|
GPS_RATE_MS: GPS update rate in milliseconds
Note: This parameter is for advanced users
Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
Range |
Values |
Units |
50 - 200 |
Value |
Meaning |
100 |
10Hz |
125 |
8Hz |
200 |
5Hz |
|
milliseconds |
GPS_RATE_MS2: GPS 2 update rate in milliseconds
Note: This parameter is for advanced users
Controls how often the GPS should provide a position update. Lowering below 5Hz is not allowed
Range |
Values |
Units |
50 - 200 |
Value |
Meaning |
100 |
10Hz |
125 |
8Hz |
200 |
5Hz |
|
milliseconds |
GPS_POS1_X: Antenna X position offset
Note: This parameter is for advanced users
X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_POS1_Y: Antenna Y position offset
Note: This parameter is for advanced users
Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_POS1_Z: Antenna Z position offset
Note: This parameter is for advanced users
Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_POS2_X: Antenna X position offset
Note: This parameter is for advanced users
X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_POS2_Y: Antenna Y position offset
Note: This parameter is for advanced users
Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_POS2_Z: Antenna Z position offset
Note: This parameter is for advanced users
Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
Range |
Units |
-10 - 10 |
meters |
GPS_DELAY_MS: GPS delay in milliseconds
Note: This parameter is for advanced users
Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
Range |
Units |
RebootRequired |
0 - 250 |
milliseconds |
True |
GPS_DELAY_MS2: GPS 2 delay in milliseconds
Note: This parameter is for advanced users
Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
Range |
Units |
RebootRequired |
0 - 250 |
milliseconds |
True |
GPS_BLEND_MASK: Multi GPS Blending Mask
Note: This parameter is for advanced users
Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2
Bitmask |
Bit |
Meaning |
0 |
Horiz Pos |
1 |
Vert Pos |
2 |
Speed |
|
GPS_BLEND_TC: Blending time constant
Note: This parameter is for advanced users
Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
Range |
Units |
5.0 - 30.0 |
seconds |
INS_ Parameters
INS_GYROFFS_X: Gyro offsets of X axis
Note: This parameter is for advanced users
Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations
INS_GYROFFS_Y: Gyro offsets of Y axis
Note: This parameter is for advanced users
Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations
INS_GYROFFS_Z: Gyro offsets of Z axis
Note: This parameter is for advanced users
Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations
INS_GYR2OFFS_X: Gyro2 offsets of X axis
Note: This parameter is for advanced users
Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations
INS_GYR2OFFS_Y: Gyro2 offsets of Y axis
Note: This parameter is for advanced users
Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
INS_GYR2OFFS_Z: Gyro2 offsets of Z axis
Note: This parameter is for advanced users
Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
INS_GYR3OFFS_X: Gyro3 offsets of X axis
Note: This parameter is for advanced users
Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations
INS_GYR3OFFS_Y: Gyro3 offsets of Y axis
Note: This parameter is for advanced users
Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
INS_GYR3OFFS_Z: Gyro3 offsets of Z axis
Note: This parameter is for advanced users
Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
INS_ACCSCAL_X: Accelerometer scaling of X axis
Note: This parameter is for advanced users
Accelerometer scaling of X axis. Calculated during acceleration calibration routine
INS_ACCSCAL_Y: Accelerometer scaling of Y axis
Note: This parameter is for advanced users
Accelerometer scaling of Y axis Calculated during acceleration calibration routine
INS_ACCSCAL_Z: Accelerometer scaling of Z axis
Note: This parameter is for advanced users
Accelerometer scaling of Z axis Calculated during acceleration calibration routine
INS_ACCOFFS_X: Accelerometer offsets of X axis
Note: This parameter is for advanced users
Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACCOFFS_Y: Accelerometer offsets of Y axis
Note: This parameter is for advanced users
Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACCOFFS_Z: Accelerometer offsets of Z axis
Note: This parameter is for advanced users
Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC2SCAL_X: Accelerometer2 scaling of X axis
Note: This parameter is for advanced users
Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine
INS_ACC2SCAL_Y: Accelerometer2 scaling of Y axis
Note: This parameter is for advanced users
Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine
INS_ACC2SCAL_Z: Accelerometer2 scaling of Z axis
Note: This parameter is for advanced users
Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine
INS_ACC2OFFS_X: Accelerometer2 offsets of X axis
Note: This parameter is for advanced users
Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC2OFFS_Y: Accelerometer2 offsets of Y axis
Note: This parameter is for advanced users
Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC2OFFS_Z: Accelerometer2 offsets of Z axis
Note: This parameter is for advanced users
Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC3SCAL_X: Accelerometer3 scaling of X axis
Note: This parameter is for advanced users
Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine
INS_ACC3SCAL_Y: Accelerometer3 scaling of Y axis
Note: This parameter is for advanced users
Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine
INS_ACC3SCAL_Z: Accelerometer3 scaling of Z axis
Note: This parameter is for advanced users
Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine
INS_ACC3OFFS_X: Accelerometer3 offsets of X axis
Note: This parameter is for advanced users
Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC3OFFS_Y: Accelerometer3 offsets of Y axis
Note: This parameter is for advanced users
Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_ACC3OFFS_Z: Accelerometer3 offsets of Z axis
Note: This parameter is for advanced users
Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations
Range |
Units |
-3.5 - 3.5 |
meters per square second |
INS_GYRO_FILTER: Gyro filter cutoff frequency
Note: This parameter is for advanced users
Filter cutoff frequency for gyroscopes. This can be set to a lower value to try to cope with very high vibration levels in aircraft. This option takes effect on the next reboot. A value of zero means no filtering (not recommended!)
Range |
Units |
0 - 127 |
hertz |
INS_ACCEL_FILTER: Accel filter cutoff frequency
Note: This parameter is for advanced users
Filter cutoff frequency for accelerometers. This can be set to a lower value to try to cope with very high vibration levels in aircraft. This option takes effect on the next reboot. A value of zero means no filtering (not recommended!)
Range |
Units |
0 - 127 |
hertz |
INS_USE: Use first IMU for attitude, velocity and position estimates
Note: This parameter is for advanced users
Use first IMU for attitude, velocity and position estimates
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
INS_USE2: Use second IMU for attitude, velocity and position estimates
Note: This parameter is for advanced users
Use second IMU for attitude, velocity and position estimates
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
INS_USE3: Use third IMU for attitude, velocity and position estimates
Note: This parameter is for advanced users
Use third IMU for attitude, velocity and position estimates
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
INS_STILL_THRESH: Stillness threshold for detecting if we are moving
Note: This parameter is for advanced users
Threshold to tolerate vibration to determine if vehicle is motionless. This depends on the frame type and if there is a constant vibration due to motors before launch or after landing. Total motionless is about 0.05. Suggested values: Planes/rover use 0.1, multirotors use 1, tradHeli uses 5
INS_GYR_CAL: Gyro Calibration scheme
Note: This parameter is for advanced users
Conrols when automatic gyro calibration is performed
Values |
Value |
Meaning |
0 |
Never |
1 |
Start-up only |
|
INS_TRIM_OPTION: Accel cal trim option
Note: This parameter is for advanced users
Specifies how the accel cal routine determines the trims
Values |
Value |
Meaning |
0 |
Don’t adjust the trims |
1 |
Assume first orientation was level |
2 |
Assume ACC_BODYFIX is perfectly aligned to the vehicle |
|
INS_ACC_BODYFIX: Body-fixed accelerometer
Note: This parameter is for advanced users
The body-fixed accelerometer to be used for trim calculation
Values |
Value |
Meaning |
1 |
IMU 1 |
2 |
IMU 2 |
3 |
IMU 3 |
|
INS_POS1_X: IMU accelerometer X position
Note: This parameter is for advanced users
X position of the first IMU Accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS1_Y: IMU accelerometer Y position
Note: This parameter is for advanced users
Y position of the first IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS1_Z: IMU accelerometer Z position
Note: This parameter is for advanced users
Z position of the first IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS2_X: IMU accelerometer X position
Note: This parameter is for advanced users
X position of the second IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS2_Y: IMU accelerometer Y position
Note: This parameter is for advanced users
Y position of the second IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS2_Z: IMU accelerometer Z position
Note: This parameter is for advanced users
Z position of the second IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS3_X: IMU accelerometer X position
Note: This parameter is for advanced users
X position of the third IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS3_Y: IMU accelerometer Y position
Note: This parameter is for advanced users
Y position of the third IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_POS3_Z: IMU accelerometer Z position
Note: This parameter is for advanced users
Z position of the third IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Range |
Units |
-10 - 10 |
meters |
INS_GYR_ID: Gyro ID
Note: This parameter is for advanced users
Gyro sensor ID, taking into account its type, bus and instance
INS_GYR2_ID: Gyro2 ID
Note: This parameter is for advanced users
Gyro2 sensor ID, taking into account its type, bus and instance
INS_GYR3_ID: Gyro3 ID
Note: This parameter is for advanced users
Gyro3 sensor ID, taking into account its type, bus and instance
INS_ACC_ID: Accelerometer ID
Note: This parameter is for advanced users
Accelerometer sensor ID, taking into account its type, bus and instance
INS_ACC2_ID: Accelerometer2 ID
Note: This parameter is for advanced users
Accelerometer2 sensor ID, taking into account its type, bus and instance
INS_ACC3_ID: Accelerometer3 ID
Note: This parameter is for advanced users
Accelerometer3 sensor ID, taking into account its type, bus and instance
INS_FAST_SAMPLE: Fast sampling mask
Note: This parameter is for advanced users
Mask of IMUs to enable fast sampling on, if available
Bitmask |
Values |
Bit |
Meaning |
0 |
FirstIMU |
1 |
SecondIMU |
2 |
ThirdIMU |
|
Value |
Meaning |
1 |
FirstIMUOnly |
3 |
FirstAndSecondIMU |
|
SERIAL Parameters
SERIAL0_BAUD: Serial0 baud rate
The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
460 |
460800 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL0_PROTOCOL: Console protocol selection
Control what protocol to use on the console.
Values |
RebootRequired |
Value |
Meaning |
1 |
MAVlink1 |
2 |
MAVLink2 |
|
True |
SERIAL1_PROTOCOL: Telem1 protocol selection
Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL1_BAUD: Telem1 Baud Rate
The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL2_PROTOCOL: Telemetry 2 protocol selection
Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL2_BAUD: Telemetry 2 Baud Rate
The baud rate of the Telem2 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL3_PROTOCOL: Serial 3 (GPS) protocol selection
Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL3_BAUD: Serial 3 (GPS) Baud Rate
The baud rate used for the Serial 3 (GPS). Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL4_PROTOCOL: Serial4 protocol selection
Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL4_BAUD: Serial 4 Baud Rate
The baud rate used for Serial4. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL5_PROTOCOL: Serial5 protocol selection
Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL5_BAUD: Serial 5 Baud Rate
The baud rate used for Serial5. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL6_PROTOCOL: Serial6 protocol selection
Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Values |
RebootRequired |
Value |
Meaning |
-1 |
None |
1 |
MAVLink1 |
2 |
MAVLink2 |
3 |
Frsky D |
4 |
Frsky SPort |
5 |
GPS |
7 |
Alexmos Gimbal Serial |
8 |
SToRM32 Gimbal Serial |
9 |
Rangefinder |
10 |
FrSky SPort Passthrough (OpenTX) |
11 |
Lidar360 |
13 |
Beacon |
14 |
Volz servo out |
15 |
SBus servo out |
16 |
ESC Telemetry |
17 |
Devo Telemetry |
18 |
OpticalFlow |
19 |
RobotisServo |
|
True |
SERIAL6_BAUD: Serial 6 Baud Rate
The baud rate used for Serial6. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can’t connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Values |
Value |
Meaning |
1 |
1200 |
2 |
2400 |
4 |
4800 |
9 |
9600 |
19 |
19200 |
38 |
38400 |
57 |
57600 |
111 |
111100 |
115 |
115200 |
256 |
256000 |
500 |
500000 |
921 |
921600 |
1500 |
1500000 |
|
SERIAL1_OPTIONS: Telem1 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL2_OPTIONS: Telem2 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL3_OPTIONS: Serial3 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL4_OPTIONS: Serial4 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL5_OPTIONS: Serial5 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL6_OPTIONS: Serial6 options
Note: This parameter is for advanced users
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Bitmask |
RebootRequired |
Bit |
Meaning |
0 |
InvertRX |
1 |
InvertTX |
2 |
HalfDuplex |
4 |
Swap |
|
True |
SERIAL_PASS1: Serial passthru first port
Note: This parameter is for advanced users
This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
Values |
Value |
Meaning |
-1 |
Disabled |
0 |
Serial0 |
1 |
Serial1 |
2 |
Serial2 |
3 |
Serial3 |
4 |
Serial4 |
5 |
Serial5 |
6 |
Serial6 |
|
SERIAL_PASS2: Serial passthru second port
Note: This parameter is for advanced users
This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
Values |
Value |
Meaning |
-1 |
Disabled |
0 |
Serial0 |
1 |
Serial1 |
2 |
Serial2 |
3 |
Serial3 |
4 |
Serial4 |
5 |
Serial5 |
6 |
Serial6 |
|
SERIAL_PASSTIMO: Serial passthru timeout
Note: This parameter is for advanced users
This sets a timeout for serial pass-through in seconds. When the pass-through is enabled by setting the SERIAL_PASS1 and SERIAL_PASS2 parameters then it remains in effect until no data comes from the first port for SERIAL_PASSTIMO seconds. This allows the port to revent to its normal usage (such as MAVLink connection to a GCS) when it is no longer needed. A value of 0 means no timeout.
Range |
Units |
0 - 120 |
seconds |