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.
Rover Parameters
LOG_BITMASK: Log bitmask
Note: This parameter is for advanced users
Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all log types by setting this to 65535. The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Rangefinder=16384, Arming=32768, FullLogs=65535
Bitmask |
Bit |
Meaning |
0 |
ATTITUDE_FAST |
1 |
ATTITUDE_MED |
2 |
GPS |
3 |
PM |
4 |
THR |
5 |
NTUN |
7 |
IMU |
8 |
CMD |
9 |
CURRENT |
10 |
RANGEFINDER |
11 |
COMPASS |
12 |
CAMERA |
13 |
STEERING |
14 |
RC |
15 |
ARM/DISARM |
19 |
IMU_RAW |
20 |
VideoStabilization |
|
RST_SWITCH_CH: Reset Switch Channel
Note: This parameter is for advanced users
RC channel to use to reset to last flight mode after geofence takeover.
INITIAL_MODE: Initial driving mode
Note: This parameter is for advanced users
This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
SYSID_THISMAV: MAVLink system ID of this vehicle
Note: This parameter is for advanced users
Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
SYSID_MYGCS: MAVLink ground station 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.
TELEM_DELAY: Telemetry startup delay
The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
Increment |
Range |
Units |
1 |
0 - 30 |
seconds |
GCS_PID_MASK: GCS PID tuning mask
Note: This parameter is for advanced users
bitmask of PIDs to send MAVLink PID_TUNING messages for
Bitmask |
Values |
Bit |
Meaning |
0 |
Steering |
1 |
Throttle |
2 |
Pitch |
3 |
Left Wheel |
4 |
Right Wheel |
5 |
Sailboat Heel |
6 |
Velocity North |
7 |
Velocity East |
|
Value |
Meaning |
0 |
None |
1 |
Steering |
2 |
Throttle |
4 |
Pitch |
8 |
Left Wheel |
16 |
Right Wheel |
32 |
Sailboat Heel |
64 |
Velocity North |
128 |
Velocity East |
|
AUTO_TRIGGER_PIN: Auto mode trigger pin
pin number to use to enable the throttle in auto mode. If set to -1 then don’t use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a ‘press button to start’ rover with no receiver.
Values |
Value |
Meaning |
-1 |
Disabled |
0 |
APM TriggerPin0 |
1 |
APM TriggerPin1 |
2 |
APM TriggerPin2 |
3 |
APM TriggerPin3 |
4 |
APM TriggerPin4 |
5 |
APM TriggerPin5 |
6 |
APM TriggerPin6 |
7 |
APM TriggerPin7 |
8 |
APM TriggerPin8 |
50 |
AUX1 |
51 |
AUX2 |
52 |
AUX3 |
53 |
AUX4 |
54 |
AUX5 |
55 |
AUX6 |
|
AUTO_KICKSTART: Auto mode trigger kickstart acceleration
X acceleration in meters/second/second to use to trigger the motor start in auto mode. If set to zero then auto throttle starts immediately when the mode switch happens, otherwise the rover waits for the X acceleration to go above this value before it will start the motor
Increment |
Range |
Units |
0.1 |
0 - 20 |
meters per square second |
CRUISE_SPEED: Target cruise speed in auto modes
The target speed in auto missions.
Increment |
Range |
Units |
0.1 |
0 - 100 |
meters per second |
CRUISE_THROTTLE: Base throttle percentage in auto
The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.
Increment |
Range |
Units |
1 |
0 - 100 |
percent |
FS_ACTION: Failsafe Action
What to do on a failsafe event
Values |
Value |
Meaning |
0 |
Nothing |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL or RTL |
4 |
SmartRTL or Hold |
|
FS_TIMEOUT: Failsafe timeout
The time in seconds that a failsafe condition must persist before the failsafe action is triggered
Increment |
Range |
Units |
0.5 |
1 - 100 |
seconds |
FS_THR_ENABLE: Throttle Failsafe Enable
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range. Failsafe will be triggered when the throttle channel goes below the FS_THR_VALUE for FS_TIMEOUT seconds.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Enabled Continue with Mission in Auto |
|
FS_THR_VALUE: Throttle Failsafe Value
The PWM level on the throttle channel below which throttle failsafe triggers.
Increment |
Range |
1 |
910 - 1100 |
FS_GCS_ENABLE: GCS failsafe enable
Enable ground control station telemetry failsafe. When enabled the Rover will execute the FS_ACTION when it fails to receive MAVLink heartbeat packets for FS_TIMEOUT seconds.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Enabled Continue with Mission in Auto |
|
FS_CRASH_CHECK: Crash check action
What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Hold |
2 |
HoldAndDisarm |
|
FS_EKF_ACTION: EKF Failsafe Action
Note: This parameter is for advanced users
Controls the action that will be taken when an EKF failsafe is invoked
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Hold |
2 |
ReportOnly |
|
FS_EKF_THRESH: EKF failsafe variance threshold
Note: This parameter is for advanced users
Allows setting the maximum acceptable compass and velocity variance
Values |
Value |
Meaning |
0.6 |
Strict |
0.8 |
Default |
1.0 |
Relaxed |
|
MODE_CH: Mode channel
Note: This parameter is for advanced users
RC Channel to use for driving mode control
MODE1: Mode1
Driving mode for switch position 1 (910 to 1230 and above 2049)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE2: Mode2
Driving mode for switch position 2 (1231 to 1360)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE3: Mode3
Driving mode for switch position 3 (1361 to 1490)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE4: Mode4
Driving mode for switch position 4 (1491 to 1620)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE5: Mode5
Driving mode for switch position 5 (1621 to 1749)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE6: Mode6
Driving mode for switch position 6 (1750 to 2049)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
SYSID_ENFORCE: GCS sysid enforcement
Note: This parameter is for advanced users
This controls whether packets from other than the expected GCS system ID will be accepted
Values |
Value |
Meaning |
0 |
NotEnforced |
1 |
Enforced |
|
TURN_RADIUS: Turn radius of vehicle
Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
Increment |
Range |
Units |
0.1 |
0 - 10 |
meters |
ACRO_TURN_RATE: Acro mode turn rate maximum
Acro mode turn rate maximum
Increment |
Range |
Units |
1 |
0 - 360 |
degrees per second |
RTL_SPEED: Return-to-Launch speed default
Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
Increment |
Range |
Units |
0.1 |
0 - 100 |
meters per second |
FRAME_CLASS: Frame Class
Frame Class
Values |
Value |
Meaning |
0 |
Undefined |
1 |
Rover |
2 |
Boat |
3 |
BalanceBot |
|
BAL_PITCH_MAX: BalanceBot Maximum Pitch
Pitch angle in degrees at 100% throttle
Increment |
Range |
Units |
0.1 |
0 - 5 |
degrees |
CRASH_ANGLE: Crash Angle
Pitch/Roll angle limit in degrees for crash check. Zero disables check
Increment |
Range |
Units |
1 |
0 - 60 |
degrees |
FRAME_TYPE: Frame Type
Note: Reboot required after change
Frame Type
Values |
Value |
Meaning |
0 |
Undefined |
1 |
Omni3 |
2 |
OmniX |
3 |
OmniPlus |
|
LOIT_TYPE: Loiter type
Loiter behaviour when moving to the target point
Values |
Value |
Meaning |
0 |
Forward or reverse to target point |
1 |
Always face bow towards target point |
2 |
Always face stern towards target point |
|
SIMPLE_TYPE: Simple_Type
Note: Reboot required after change
Simple mode types
Values |
Value |
Meaning |
0 |
InitialHeading |
1 |
CardinalDirections |
|
LOIT_RADIUS: Loiter radius
Vehicle will drift when within this distance of the target position
Increment |
Range |
Units |
1 |
0 - 20 |
meters |
MIS_DONE_BEHAVE: Mission done behave
Behaviour after mission completes
Values |
Value |
Meaning |
0 |
Hold |
1 |
Loiter |
2 |
Acro |
3 |
Manual |
|
BAL_PITCH_TRIM: Balance Bot pitch trim angle
Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
Increment |
Range |
Units |
0.1 |
-2 - 2 |
degrees |
STICK_MIXING: Stick Mixing
Note: This parameter is for advanced users
When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
SPEED_MAX: Speed maximum
Note: This parameter is for advanced users
Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.
Increment |
Range |
Units |
0.1 |
0 - 30 |
meters per second |
LOIT_SPEED_GAIN: Loiter speed gain
Note: This parameter is for advanced users
Determines how agressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.
Increment |
Range |
0.01 |
0 - 5 |
FS_OPTIONS: Failsafe Options
Note: This parameter is for advanced users
Bitmask to enable failsafe options
Bitmask |
Values |
Bit |
Meaning |
0 |
Failsafe enabled in Hold mode |
|
Value |
Meaning |
0 |
None |
1 |
Failsafe enabled in Hold mode |
|
GUID_OPTIONS: Guided mode options
Note: This parameter is for advanced users
Options that can be applied to change guided mode behaviour
Bitmask |
Bit |
Meaning |
6 |
SCurves used for navigation |
|
CH7_OPTION: Channel 7 option
What to do use channel 7 for
Values |
Value |
Meaning |
0 |
Nothing |
1 |
SaveWaypoint |
2 |
LearnCruiseSpeed |
3 |
ArmDisarm |
4 |
Manual |
5 |
Acro |
6 |
Steering |
7 |
Hold |
8 |
Auto |
9 |
RTL |
10 |
SmartRTL |
11 |
Guided |
12 |
Loiter |
|
AUX_CH: Auxiliary switch channel
Note: This parameter is for advanced users
RC Channel to use for auxiliary functions including saving waypoints
PIVOT_TURN_ANGLE: Pivot turn angle
Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.
Increment |
Range |
Units |
1 |
0 - 360 |
degrees |
PIVOT_TURN_RATE: Pivot turn rate
Desired pivot turn rate in deg/s.
Increment |
Range |
Units |
1 |
0 - 360 |
degrees per second |
AFS_ Parameters
AFS_ENABLE: Enable Advanced Failsafe
Note: This parameter is for advanced users
This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
AFS_MAN_PIN: Manual Pin
Note: This parameter is for advanced users
This sets a digital output pin to set high when in manual mode. See the Wiki’s “GPIOs” page for how to determine the pin number for a given autopilot.
AFS_HB_PIN: Heartbeat Pin
Note: This parameter is for advanced users
This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki’s “GPIOs” page for how to determine the pin number for a given autopilot.
Values |
Value |
Meaning |
-1 |
Disabled |
49 |
BB Blue GP0 pin 4 |
50 |
AUXOUT1 |
51 |
AUXOUT2 |
52 |
AUXOUT3 |
53 |
AUXOUT4 |
54 |
AUXOUT5 |
55 |
AUXOUT6 |
57 |
BB Blue GP0 pin 3 |
113 |
BB Blue GP0 pin 6 |
116 |
BB Blue GP0 pin 5 |
|
AFS_WP_COMMS: Comms Waypoint
Note: This parameter is for advanced users
Waypoint number to navigate to on comms loss
AFS_WP_GPS_LOSS: GPS Loss Waypoint
Note: This parameter is for advanced users
Waypoint number to navigate to on GPS lock loss
AFS_TERMINATE: Force Terminate
Note: This parameter is for advanced users
Can be set in flight to force termination of the heartbeat signal
AFS_TERM_ACTION: Terminate action
Note: This parameter is for advanced users
This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter
AFS_TERM_PIN: Terminate Pin
Note: This parameter is for advanced users
This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki’s “GPIOs” page for how to determine the pin number for a given autopilot.
Values |
Value |
Meaning |
-1 |
Disabled |
49 |
BB Blue GP0 pin 4 |
50 |
AUXOUT1 |
51 |
AUXOUT2 |
52 |
AUXOUT3 |
53 |
AUXOUT4 |
54 |
AUXOUT5 |
55 |
AUXOUT6 |
57 |
BB Blue GP0 pin 3 |
113 |
BB Blue GP0 pin 6 |
116 |
BB Blue GP0 pin 5 |
|
AFS_AMSL_LIMIT: AMSL limit
Note: This parameter is for advanced users
This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
AFS_AMSL_ERR_GPS: Error margin for GPS based AMSL limit
Note: This parameter is for advanced users
This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
AFS_QNH_PRESSURE: QNH pressure
Note: This parameter is for advanced users
This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
AFS_MAX_GPS_LOSS: Maximum number of GPS loss events
Note: This parameter is for advanced users
Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
AFS_GEOFENCE: Enable geofence Advanced Failsafe
Note: This parameter is for advanced users
This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC: Enable RC Advanced Failsafe
Note: This parameter is for advanced users
This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC_MAN_ONLY: Enable RC Termination only in manual control modes
Note: This parameter is for advanced users
If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
AFS_DUAL_LOSS: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
Note: This parameter is for advanced users
This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a “dual loss” and cause termination.
AFS_RC_FAIL_TIME: RC failure time
Note: This parameter is for advanced users
This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
AFS_MAX_RANGE: Max allowed range
Note: This parameter is for advanced users
This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
AHRS_ Parameters
AHRS_GPS_GAIN: AHRS GPS gain
Note: This parameter is for advanced users
This controls how much to use the GPS to correct the attitude. This should never be set to zero for a plane as it would result in the plane losing control in turns. For a plane please use the default value of 1.0.
Increment |
Range |
.01 |
0.0 - 1.0 |
AHRS_GPS_USE: AHRS use GPS for DCM navigation and position-down
Note: This parameter is for advanced users
This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won’t be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS according to its own parameters. A value of 2 means to use GPS for height as well as position - both in DCM estimation and when determining altitude-above-home.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Use GPS for DCM position |
2 |
Use GPS for DCM position and height |
|
AHRS_YAW_P: Yaw P
Note: This parameter is for advanced users
This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly.
Increment |
Range |
.01 |
0.1 - 0.4 |
AHRS_RP_P: AHRS RP_P
Note: This parameter is for advanced users
This controls how fast the accelerometers correct the attitude
Increment |
Range |
.01 |
0.1 - 0.4 |
AHRS_WIND_MAX: Maximum wind
Note: This parameter is for advanced users
This sets the maximum allowable difference between ground speed and airspeed. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is. See ARSPD_OPTIONS and ARSPD_MAX_WIND to disable airspeed sensors.
Increment |
Range |
Units |
1 |
0 - 127 |
meters per second |
AHRS_TRIM_X: AHRS Trim Roll
Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.
Increment |
Range |
Units |
0.01 |
-0.1745 - +0.1745 |
radians |
AHRS_TRIM_Y: AHRS Trim Pitch
Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.
Increment |
Range |
Units |
0.01 |
-0.1745 - +0.1745 |
radians |
AHRS_TRIM_Z: AHRS Trim Yaw
Note: This parameter is for advanced users
Not Used
Increment |
Range |
Units |
0.01 |
-0.1745 - +0.1745 |
radians |
AHRS_ORIENTATION: Board Orientation
Note: This parameter is for advanced users
Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. The label for each option is specified in the order of rotations for that orientation. This option takes affect on next boot. After changing you will need to re-level your vehicle.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Yaw45Roll180 |
10 |
Yaw90Roll180 |
11 |
Yaw135Roll180 |
12 |
Pitch180 |
13 |
Yaw225Roll180 |
14 |
Yaw270Roll180 |
15 |
Yaw315Roll180 |
16 |
Roll90 |
17 |
Yaw45Roll90 |
18 |
Yaw90Roll90 |
19 |
Yaw135Roll90 |
20 |
Roll270 |
21 |
Yaw45Roll270 |
22 |
Yaw90Roll270 |
23 |
Yaw135Roll270 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Yaw90Pitch180 |
27 |
Yaw270Pitch180 |
28 |
Pitch90Roll90 |
29 |
Pitch90Roll180 |
30 |
Pitch90Roll270 |
31 |
Pitch180Roll90 |
32 |
Pitch180Roll270 |
33 |
Pitch270Roll90 |
34 |
Pitch270Roll180 |
35 |
Pitch270Roll270 |
36 |
Yaw90Pitch180Roll90 |
37 |
Yaw270Roll90 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Pitch315Roll90 |
42 |
Roll45 |
43 |
Roll315 |
100 |
Custom 4.1 and older |
101 |
Custom 1 |
102 |
Custom 2 |
|
AHRS_COMP_BETA: AHRS Velocity Complementary Filter Beta Coefficient
Note: This parameter is for advanced users
This controls the time constant for the cross-over frequency used to fuse AHRS (airspeed and heading) and GPS data to estimate ground velocity. Time constant is 0.1/beta. A larger time constant will use GPS data less and a small time constant will use air data less.
Increment |
Range |
.01 |
0.001 - 0.5 |
AHRS_GPS_MINSATS: AHRS GPS Minimum satellites
Note: This parameter is for advanced users
Minimum number of satellites visible to use GPS for velocity based corrections attitude correction. This defaults to 6, which is about the point at which the velocity numbers from a GPS become too unreliable for accurate correction of the accelerometers.
AHRS_EKF_TYPE: Use NavEKF Kalman filter for attitude and position estimation
Note: This parameter is for advanced users
This controls which NavEKF Kalman filter version is used for attitude and position estimation
Values |
Value |
Meaning |
0 |
Disabled |
2 |
Enable EKF2 |
3 |
Enable EKF3 |
11 |
ExternalAHRS |
|
AHRS_CUSTOM_ROLL: Board orientation roll offset
Note: This parameter is for advanced users
Autopilot mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Increment |
Range |
Units |
1 |
-180 - 180 |
degrees |
AHRS_CUSTOM_PIT: Board orientation pitch offset
Note: This parameter is for advanced users
Autopilot mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Increment |
Range |
Units |
1 |
-180 - 180 |
degrees |
AHRS_CUSTOM_YAW: Board orientation yaw offset
Note: This parameter is for advanced users
Autopilot mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Increment |
Range |
Units |
1 |
-180 - 180 |
degrees |
ARMING_ Parameters
ARMING_REQUIRE: Require Arming Motors
Note: This parameter is for advanced users
Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
THR_MIN PWM when disarmed |
2 |
0 PWM when disarmed |
|
ARMING_ACCTHRESH: Accelerometer error threshold
Note: This parameter is for advanced users
Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
Range |
Units |
0.25 - 3.0 |
meters per square second |
ARMING_RUDDER: Arming with Rudder enable/disable
Note: This parameter is for advanced users
Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ)
Values |
Value |
Meaning |
0 |
Disabled |
1 |
ArmingOnly |
2 |
ArmOrDisarm |
|
ARMING_MIS_ITEMS: Required mission items
Note: This parameter is for advanced users
Bitmask of mission items that are required to be planned in order to arm the aircraft
Bitmask |
Bit |
Meaning |
0 |
Land |
1 |
VTOL Land |
2 |
DO_LAND_START |
3 |
Takeoff |
4 |
VTOL Takeoff |
5 |
Rallypoint |
|
ARSPD Parameters
ARSPD_TYPE: Airspeed type
Type of airspeed sensor
Values |
Value |
Meaning |
0 |
None |
1 |
I2C-MS4525D0 |
2 |
Analog |
3 |
I2C-MS5525 |
4 |
I2C-MS5525 (0x76) |
5 |
I2C-MS5525 (0x77) |
6 |
I2C-SDP3X |
7 |
I2C-DLVR-5in |
8 |
DroneCAN |
9 |
I2C-DLVR-10in |
10 |
I2C-DLVR-20in |
11 |
I2C-DLVR-30in |
12 |
I2C-DLVR-60in |
13 |
NMEA water speed |
14 |
MSP |
15 |
ASP5033 |
|
ARSPD_DEVID: Airspeed ID
Note: This parameter is for advanced users
Airspeed sensor ID, taking into account its type, bus and instance
ARSPD_USE: Airspeed use
This parameter is not used by this vehicle. Always set to 0.
Values |
Value |
Meaning |
0 |
DoNotUse |
1 |
Use |
2 |
UseWhenZeroThrottle |
|
ARSPD_OFFSET: Airspeed offset
Note: This parameter is for advanced users
Airspeed calibration offset
ARSPD_RATIO: Airspeed ratio
Note: This parameter is for advanced users
Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.
ARSPD_PIN: Airspeed pin
Note: This parameter is for advanced users
The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
ARSPD_TUBE_ORDER: Control pitot tube order
Note: This parameter is for advanced users
This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.
Values |
Value |
Meaning |
0 |
Normal |
1 |
Swapped |
2 |
Auto Detect |
|
ARSPD_SKIP_CAL: Skip airspeed offset calibration on startup
Note: This parameter is for advanced users
This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ARSPD_PSI_RANGE: The PSI range of the device
Note: This parameter is for advanced users
This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
ARSPD_BUS: Airspeed I2C bus
Note: This parameter is for advanced users
Bus number of the I2C bus where the airspeed sensor is connected
Values |
Value |
Meaning |
0 |
Bus0(internal) |
1 |
Bus1(external) |
2 |
Bus2(auxiliary) |
|
ARSPD_PRIMARY: Primary airspeed sensor
Note: This parameter is for advanced users
This selects which airspeed sensor will be the primary if multiple sensors are found
Values |
Value |
Meaning |
0 |
FirstSensor |
1 |
2ndSensor |
|
ARSPD_OPTIONS: Airspeed options bitmask
Note: This parameter is for advanced users
This parameter and function is not used by this vehicle. Always set to 0.
Bitmask |
Bit |
Meaning |
0 |
SpeedMismatchDisable |
1 |
AllowSpeedMismatchRecovery |
2 |
DisableVoltageCorrection |
|
ARSPD_WIND_MAX: Maximum airspeed and ground speed difference
Note: This parameter is for advanced users
This parameter and function is not used by this vehicle. Always set to 0.
ARSPD_WIND_WARN: Airspeed and ground speed difference that gives a warning
Note: This parameter is for advanced users
This parameter and function is not used by this vehicle. Always set to 0.
ARSPD2_TYPE: Second Airspeed type
Type of 2nd airspeed sensor
Values |
Value |
Meaning |
0 |
None |
1 |
I2C-MS4525D0 |
2 |
Analog |
3 |
I2C-MS5525 |
4 |
I2C-MS5525 (0x76) |
5 |
I2C-MS5525 (0x77) |
6 |
I2C-SDP3X |
7 |
I2C-DLVR-5in |
8 |
DroneCAN |
9 |
I2C-DLVR-10in |
10 |
I2C-DLVR-20in |
11 |
I2C-DLVR-30in |
12 |
I2C-DLVR-60in |
13 |
NMEA water speed |
14 |
MSP |
15 |
ASP5033 |
|
ARSPD2_USE: Enable use of 2nd airspeed sensor
This parameter and function is not used by this vehicle. Always set to 0.
Values |
Value |
Meaning |
0 |
Don’t Use |
1 |
use |
2 |
UseWhenZeroThrottle |
|
ARSPD2_OFFSET: Airspeed offset for 2nd airspeed sensor
Note: This parameter is for advanced users
Airspeed calibration offset
ARSPD2_RATIO: Airspeed ratio for 2nd airspeed sensor
Note: This parameter is for advanced users
Airspeed calibration ratio
ARSPD2_PIN: Airspeed pin for 2nd airspeed sensor
Note: This parameter is for advanced users
Pin number indicating location of analog airspeed sensors. Pixhawk/Cube if set to 15.
ARSPD2_AUTOCAL: Automatic airspeed ratio calibration for 2nd airspeed sensor
Note: This parameter is for advanced users
This parameter and function is not used by this vehicle. Always set to 0.
ARSPD2_TUBE_ORDR: Control pitot tube order of 2nd airspeed sensor
Note: This parameter is for advanced users
This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.
Values |
Value |
Meaning |
0 |
Normal |
1 |
Swapped |
2 |
Auto Detect |
|
ARSPD2_SKIP_CAL: Skip airspeed offset calibration on startup for 2nd sensor
Note: This parameter is for advanced users
This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ARSPD2_PSI_RANGE: The PSI range of the device for 2nd sensor
Note: This parameter is for advanced users
This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
ARSPD2_BUS: Airspeed I2C bus for 2nd sensor
Note: This parameter is for advanced users
The bus number of the I2C bus to look for the sensor on
Values |
Value |
Meaning |
0 |
Bus0(internal) |
1 |
Bus1(external) |
2 |
Bus2(auxiliary) |
|
ARSPD2_DEVID: Airspeed2 ID
Note: This parameter is for advanced users
Airspeed2 sensor ID, taking into account its type, bus and instance
ATC Parameters
ATC_STR_RAT_P: Steering control rate P gain
Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
Increment |
Range |
0.001 |
0.000 - 2.000 |
ATC_STR_RAT_I: Steering control I gain
Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
Increment |
Range |
0.001 |
0.000 - 2.000 |
ATC_STR_RAT_IMAX: Steering control I gain maximum
Steering control I gain maximum. Constrains the steering output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_STR_RAT_D: Steering control D gain
Steering control D gain. Compensates for short-term change in desired turn rate vs actual
Increment |
Range |
0.001 |
0.000 - 0.400 |
ATC_STR_RAT_FF: Steering control feed forward
Steering control feed forward
Increment |
Range |
0.001 |
0.000 - 3.000 |
ATC_STR_RAT_FILT: Steering control filter frequency
Steering control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTT: Steering control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTE: Steering control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTD: Steering control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_SMAX: Steering slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_SPEED_P: Speed control P gain
Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.010 - 2.000 |
ATC_SPEED_I: Speed control I gain
Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SPEED_IMAX: Speed control I gain maximum
Speed control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_SPEED_D: Speed control D gain
Speed control D gain. Compensates for short-term change in desired speed vs actual
Increment |
Range |
0.001 |
0.000 - 0.400 |
ATC_SPEED_FF: Speed control feed forward
Speed control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_SPEED_FILT: Speed control filter frequency
Speed control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTT: Speed control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTE: Speed control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTD: Speed control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_SMAX: Speed control slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_ACCEL_MAX: Speed control acceleration (and deceleration) maximum in m/s/s
Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
Increment |
Range |
Units |
0.1 |
0.0 - 10.0 |
meters per square second |
ATC_BRAKE: Speed control brake enable/disable
Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ATC_STOP_SPEED: Speed control stop speed
Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
Increment |
Range |
Units |
0.01 |
0.00 - 0.50 |
meters per second |
ATC_STR_ANG_P: Steering control angle P gain
Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
Increment |
Range |
0.1 |
1.000 - 10.000 |
ATC_STR_ACC_MAX: Steering control angular acceleration maximum
Steering control angular acceleration maximum (in deg/s/s). 0 to disable acceleration limiting
Increment |
Range |
Units |
0.1 |
0 - 1000 |
degrees per square second |
ATC_STR_RAT_MAX: Steering control rotation rate maximum
Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
Increment |
Range |
Units |
0.1 |
0 - 1000 |
degrees per second |
ATC_DECEL_MAX: Speed control deceleration maximum in m/s/s
Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
Increment |
Range |
Units |
0.1 |
0.0 - 10.0 |
meters per square second |
ATC_BAL_P: Pitch control P gain
Pitch control P gain for BalanceBots. Converts the error between the desired pitch (in radians) and actual pitch to a motor output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_BAL_I: Pitch control I gain
Pitch control I gain for BalanceBots. Corrects long term error between the desired pitch (in radians) and actual pitch
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_BAL_IMAX: Pitch control I gain maximum
Pitch control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_BAL_D: Pitch control D gain
Pitch control D gain. Compensates for short-term change in desired pitch vs actual
Increment |
Range |
0.001 |
0.000 - 0.100 |
ATC_BAL_FF: Pitch control feed forward
Pitch control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_BAL_FILT: Pitch control filter frequency
Pitch control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTT: Pitch control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTE: Pitch control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTD: Pitch control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_SMAX: Pitch control slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_BAL_SPD_FF: Pitch control feed forward from speed
Pitch control feed forward from speed
Increment |
Range |
0.01 |
0.0 - 10.0 |
ATC_SAIL_P: Sail Heel control P gain
Sail Heel control P gain for sailboats. Converts the error between the desired heel angle (in radians) and actual heel to a main sail output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SAIL_I: Sail Heel control I gain
Sail Heel control I gain for sailboats. Corrects long term error between the desired heel angle (in radians) and actual
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SAIL_IMAX: Sail Heel control I gain maximum
Sail Heel control I gain maximum. Constrains the maximum I term contribution to the main sail output (range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_SAIL_D: Sail Heel control D gain
Sail Heel control D gain. Compensates for short-term change in desired heel angle vs actual
Increment |
Range |
0.001 |
0.000 - 0.100 |
ATC_SAIL_FF: Sail Heel control feed forward
Sail Heel control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_SAIL_FILT: Sail Heel control filter frequency
Sail Heel control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTT: Sail Heel Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTE: Sail Heel Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTD: Sail Heel Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_SMAX: Sail heel slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_TURN_MAX_G: Turning maximum G force
The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
Increment |
Range |
Units |
0.01 |
0.1 - 10 |
standard acceleration due to gravity |
BARO Parameters
BARO1_GND_PRESS: Ground Pressure
Note: This parameter is for advanced users
calibrated ground pressure in Pascals
Increment |
ReadOnly |
Units |
Volatile |
1 |
True |
pascal |
True |
BARO_GND_TEMP: ground temperature
Note: This parameter is for advanced users
User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature.
Increment |
Units |
Volatile |
1 |
degrees Celsius |
True |
BARO_ALT_OFFSET: altitude offset
Note: This parameter is for advanced users
altitude offset in meters added to barometric altitude. This is used to allow for automatic adjustment of the base barometric altitude by a ground station equipped with a barometer. The value is added to the barometric altitude read by the aircraft. It is automatically reset to 0 when the barometer is calibrated on each reboot or when a preflight calibration is performed.
Increment |
Units |
0.1 |
meters |
BARO_PRIMARY: Primary barometer
Note: This parameter is for advanced users
This selects which barometer will be the primary if multiple barometers are found
Values |
Value |
Meaning |
0 |
FirstBaro |
1 |
2ndBaro |
2 |
3rdBaro |
|
BARO_EXT_BUS: External baro bus
Note: This parameter is for advanced users
This selects the bus number for looking for an I2C barometer. When set to -1 it will probe all external i2c buses based on the GND_PROBE_EXT parameter.
Values |
Value |
Meaning |
-1 |
Disabled |
0 |
Bus0 |
1 |
Bus1 |
|
BARO2_GND_PRESS: Ground Pressure
Note: This parameter is for advanced users
calibrated ground pressure in Pascals
Increment |
ReadOnly |
Units |
Volatile |
1 |
True |
pascal |
True |
BARO3_GND_PRESS: Absolute Pressure
Note: This parameter is for advanced users
calibrated ground pressure in Pascals
Increment |
ReadOnly |
Units |
Volatile |
1 |
True |
pascal |
True |
BARO_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.
Increment |
Range |
Units |
1 |
0 - 100 |
percent |
BARO_PROBE_EXT: External barometers to probe
Note: This parameter is for advanced users
This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
Bitmask |
Bit |
Meaning |
0 |
BMP085 |
1 |
BMP280 |
2 |
MS5611 |
3 |
MS5607 |
4 |
MS5637 |
5 |
FBM320 |
6 |
DPS280 |
7 |
LPS25H |
8 |
Keller |
9 |
MS5837 |
10 |
BMP388 |
11 |
SPL06 |
12 |
MSP |
|
BARO1_DEVID: Baro ID
Note: This parameter is for advanced users
Barometer sensor ID, taking into account its type, bus and instance
BARO2_DEVID: Baro ID2
Note: This parameter is for advanced users
Barometer2 sensor ID, taking into account its type, bus and instance
BARO3_DEVID: Baro ID3
Note: This parameter is for advanced users
Barometer3 sensor ID, taking into account its type, bus and instance
BARO1_WCF_ Parameters
BARO1_WCF_ENABLE: Wind coefficient enable
Note: This parameter is for advanced users
This enables the use of wind coefficients for barometer compensation
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BARO1_WCF_FWD: Pressure error coefficient in positive X direction (forward)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO1_WCF_BCK: Pressure error coefficient in negative X direction (backwards)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO1_WCF_RGT: Pressure error coefficient in positive Y direction (right)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO1_WCF_LFT: Pressure error coefficient in negative Y direction (left)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO2_WCF_ Parameters
BARO2_WCF_ENABLE: Wind coefficient enable
Note: This parameter is for advanced users
This enables the use of wind coefficients for barometer compensation
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BARO2_WCF_FWD: Pressure error coefficient in positive X direction (forward)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO2_WCF_BCK: Pressure error coefficient in negative X direction (backwards)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO2_WCF_RGT: Pressure error coefficient in positive Y direction (right)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO2_WCF_LFT: Pressure error coefficient in negative Y direction (left)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO3_WCF_ Parameters
BARO3_WCF_ENABLE: Wind coefficient enable
Note: This parameter is for advanced users
This enables the use of wind coefficients for barometer compensation
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BARO3_WCF_FWD: Pressure error coefficient in positive X direction (forward)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO3_WCF_BCK: Pressure error coefficient in negative X direction (backwards)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO3_WCF_RGT: Pressure error coefficient in positive Y direction (right)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BARO3_WCF_LFT: Pressure error coefficient in negative Y direction (left)
Note: This parameter is for advanced users
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.
Increment |
Range |
0.05 |
-1.0 - 1.0 |
BATT2_ Parameters
BATT2_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT2_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT2_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT2_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT2_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT2_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT2_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT2_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT2_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT2_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT3_ Parameters
BATT3_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT3_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT3_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT3_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT3_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT3_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT3_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT3_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT3_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT3_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT4_ Parameters
BATT4_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT4_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT4_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT4_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT4_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT4_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT4_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT4_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT4_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT4_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT5_ Parameters
BATT5_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT5_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT5_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT5_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT5_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT5_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT5_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT5_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT5_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT5_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT6_ Parameters
BATT6_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT6_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT6_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT6_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT6_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT6_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT6_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT6_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT6_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT6_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT7_ Parameters
BATT7_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT7_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT7_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT7_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT7_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT7_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT7_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT7_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT7_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT7_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT8_ Parameters
BATT8_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT8_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT8_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT8_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT8_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT8_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT8_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT8_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT8_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT8_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT9_ Parameters
BATT9_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT9_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT9_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT9_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT9_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT9_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT9_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT9_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT9_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT9_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BATT_ Parameters
BATT_MONITOR: Battery monitoring
Note: Reboot required after change
Controls enabling monitoring of the battery’s voltage and current
Values |
Value |
Meaning |
0 |
Disabled |
3 |
Analog Voltage Only |
4 |
Analog Voltage and Current |
5 |
Solo |
6 |
Bebop |
7 |
SMBus-Generic |
8 |
DroneCAN-BatteryInfo |
9 |
ESC |
10 |
Sum Of Selected Monitors |
11 |
FuelFlow |
12 |
FuelLevelPWM |
13 |
SMBUS-SUI3 |
14 |
SMBUS-SUI6 |
15 |
NeoDesign |
16 |
SMBus-Maxell |
17 |
Generator-Elec |
18 |
Generator-Fuel |
19 |
Rotoye |
20 |
MPPT |
21 |
INA2XX |
22 |
LTC2946 |
23 |
Torqeedo |
|
BATT_CAPACITY: Battery capacity
Capacity of the battery in mAh when full
Increment |
Units |
50 |
milliampere hour |
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 DroneCan 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.
Increment |
Range |
Units |
1 |
0 - 120 |
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
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
BATT_FS_CRT_ACT: Critical battery failsafe action
What action the vehicle should perform if it hits a critical battery failsafe
Values |
Value |
Meaning |
0 |
None |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL |
4 |
SmartRTL or Hold |
5 |
Terminate |
|
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 |
BATT_OPTIONS: Battery monitor options
Note: This parameter is for advanced users
This sets options to change the behaviour of the battery monitor
Bitmask |
Bit |
Meaning |
0 |
Ignore DroneCAN SoC |
1 |
MPPT reports input voltage and current |
2 |
MPPT Powered off when disarmed |
3 |
MPPT Powered on when armed |
4 |
MPPT Powered off at boot |
5 |
MPPT Powered on at boot |
6 |
Send resistance compensated voltage to GCS |
|
BATT_VOLT_PIN: Battery Voltage sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for voltage monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
2 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
5 |
Navigator |
13 |
Pixhawk2_PM2/CubeOrange_PM2 |
14 |
CubeOrange |
16 |
Durandal |
100 |
PX4-v1 |
|
BATT_CURR_PIN: Battery Current sensing pin
Note: Reboot required after change
Sets the analog input pin that should be used for current monitoring.
Values |
Value |
Meaning |
-1 |
Disabled |
3 |
Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 |
CubeOrange_PM2/Navigator |
14 |
Pixhawk2_PM2 |
15 |
CubeOrange |
17 |
Durandal |
101 |
PX4-v1 |
|
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_VLT_OFFSET: Volage offset
Note: This parameter is for advanced users
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied
BATT_I2C_BUS: Battery monitor I2C bus number
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C bus number
BATT_I2C_ADDR: Battery monitor I2C address
Note: This parameter is for advanced users
Note: Reboot required after change
Battery monitor I2C address
BATT_SUM_MASK: Battery Sum mask
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
Bit |
Meaning |
0 |
monitor 1 |
1 |
monitor 2 |
2 |
monitor 3 |
3 |
monitor 4 |
4 |
monitor 5 |
5 |
monitor 6 |
6 |
monitor 7 |
7 |
monitor 8 |
8 |
monitor 9 |
|
BATT_CURR_MULT: Scales reported power monitor current
Note: This parameter is for advanced users
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
BRD_ Parameters
BRD_SER1_RTSCTS: Serial 1 flow control
Note: This parameter is for advanced users
Note: Reboot required after change
Enable flow control on serial 1 (telemetry 1). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER2_RTSCTS: Serial 2 flow control
Note: This parameter is for advanced users
Note: Reboot required after change
Enable flow control on serial 2 (telemetry 2). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER3_RTSCTS: Serial 3 flow control
Note: This parameter is for advanced users
Note: Reboot required after change
Enable flow control on serial 3. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER4_RTSCTS: Serial 4 flow control
Note: This parameter is for advanced users
Note: Reboot required after change
Enable flow control on serial 4. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER5_RTSCTS: Serial 5 flow control
Note: This parameter is for advanced users
Note: Reboot required after change
Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SAFETYENABLE: Enable use of safety arming switch
Note: Reboot required after change
This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_SBUS_OUT: SBUS output rate
Note: This parameter is for advanced users
Note: Reboot required after change
This sets the SBUS output frame rate in Hz
Values |
Value |
Meaning |
0 |
Disabled |
1 |
50Hz |
2 |
75Hz |
3 |
100Hz |
4 |
150Hz |
5 |
200Hz |
6 |
250Hz |
7 |
300Hz |
|
BRD_SERIAL_NUM: User-defined serial number
User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
BRD_SAFETY_MASK: Outputs which ignore the safety switch state
Note: This parameter is for advanced users
Note: Reboot required after change
A bitmask which controls what outputs can move while the safety switch has not been pressed
Bitmask |
Bit |
Meaning |
0 |
Output1 |
1 |
Output2 |
2 |
Output3 |
3 |
Output4 |
4 |
Output5 |
5 |
Output6 |
6 |
Output7 |
7 |
Output8 |
8 |
Output9 |
9 |
Output10 |
10 |
Output11 |
11 |
Output12 |
12 |
Output13 |
13 |
Output14 |
|
BRD_HEAT_TARG: Board heater temperature target
Note: This parameter is for advanced users
Board heater target temperature for boards with controllable heating units. DO NOT SET to -1 on the Cube. Set to -1 to disable the heater, please reboot after setting to -1.
Range |
Units |
-1 - 80 |
degrees Celsius |
BRD_TYPE: Board type
Note: This parameter is for advanced users
Note: Reboot required after change
This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
Values |
Value |
Meaning |
0 |
AUTO |
1 |
PX4V1 |
2 |
Pixhawk |
3 |
Cube/Pixhawk2 |
4 |
Pixracer |
5 |
PixhawkMini |
6 |
Pixhawk2Slim |
13 |
Intel Aero FC |
14 |
Pixhawk Pro |
20 |
AUAV2.1 |
21 |
PCNC1 |
22 |
MINDPXV2 |
23 |
SP01 |
24 |
CUAVv5/FMUV5 |
30 |
VRX BRAIN51 |
32 |
VRX BRAIN52 |
33 |
VRX BRAIN52E |
34 |
VRX UBRAIN51 |
35 |
VRX UBRAIN52 |
36 |
VRX CORE10 |
38 |
VRX BRAIN54 |
39 |
PX4 FMUV6 |
100 |
PX4 OLDDRIVERS |
|
BRD_IO_ENABLE: Enable IO co-processor
Note: This parameter is for advanced users
Note: Reboot required after change
This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_VBUS_MIN: Autopilot board voltage requirement
Note: This parameter is for advanced users
Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
0.1 |
4.0 - 5.5 |
volt |
BRD_VSERVO_MIN: Servo voltage requirement
Note: This parameter is for advanced users
Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
0.1 |
3.3 - 12.0 |
volt |
BRD_SD_SLOWDOWN: microSD slowdown
Note: This parameter is for advanced users
This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
BRD_PWM_VOLT_SEL: Set PWM Out Voltage
Note: This parameter is for advanced users
This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output.
Values |
Value |
Meaning |
0 |
3.3V |
1 |
5V |
|
BRD_OPTIONS: Board options
Note: This parameter is for advanced users
Board specific option flags
Bitmask |
Bit |
Meaning |
0 |
Enable hardware watchdog |
1 |
Disable MAVftp |
2 |
Enable set of internal parameters |
3 |
Enable Debug Pins |
4 |
Unlock flash on reboot |
5 |
Write protect firmware flash on reboot |
6 |
Write protect bootloader flash on reboot |
|
BRD_BOOT_DELAY: Boot delay
Note: This parameter is for advanced users
This adds a delay in milliseconds to boot to ensure peripherals initialise fully
Range |
Units |
0 - 10000 |
milliseconds |
BRD_HEAT_P: Board Heater P gain
Note: This parameter is for advanced users
Board Heater P gain
Increment |
Range |
1 |
1 - 500 |
BRD_HEAT_I: Board Heater I gain
Note: This parameter is for advanced users
Board Heater integrator gain
Increment |
Range |
0.1 |
0 - 1 |
BRD_HEAT_IMAX: Board Heater IMAX
Note: This parameter is for advanced users
Board Heater integrator maximum
Increment |
Range |
1 |
0 - 100 |
BRD_ALT_CONFIG: Alternative HW config
Note: This parameter is for advanced users
Note: Reboot required after change
Select an alternative hardware configuration. A value of zero selects the default configuration for this board. Other values are board specific. Please see the documentation for your board for details on any alternative configuration values that may be available.
BRD_HEAT_LOWMGN: Board heater temp lower margin
Note: This parameter is for advanced users
Arming check will fail if temp is lower than this margin below BRD_HEAT_TARG. 0 disables the low temperature check
Range |
Units |
0 - 20 |
degrees Celsius |
BRD_RADIO Parameters
BRD_RADIO_TYPE: Set type of direct attached radio
This enables support for direct attached radio receivers
Values |
Value |
Meaning |
0 |
None |
1 |
CYRF6936 |
2 |
CC2500 |
3 |
BK2425 |
|
BRD_RADIO_PROT: protocol
Note: This parameter is for advanced users
Select air protocol
Values |
Value |
Meaning |
0 |
Auto |
1 |
DSM2 |
2 |
DSMX |
|
BRD_RADIO_DEBUG: debug level
Note: This parameter is for advanced users
radio debug level
BRD_RADIO_DISCRC: disable receive CRC
Note: This parameter is for advanced users
disable receive CRC (for debug)
Values |
Value |
Meaning |
0 |
NotDisabled |
1 |
Disabled |
|
BRD_RADIO_PPSCH: Packet rate channel
Note: This parameter is for advanced users
Channel to show received packet-per-second rate, or zero for disabled
BRD_RADIO_TELEM: Enable telemetry
Note: This parameter is for advanced users
If this is non-zero then telemetry packets will be sent over DSM
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_RADIO_TXPOW: Telemetry Transmit power
Note: This parameter is for advanced users
Set telemetry transmit power. This is the power level (from 1 to 8) for telemetry packets sent from the RX to the TX
BRD_RADIO_FCCTST: Put radio into FCC test mode
Note: This parameter is for advanced users
If this is enabled then the radio will continuously transmit as required for FCC testing. The transmit channel is set by the value of the parameter. The radio will not work for RC input while this is enabled
Values |
Value |
Meaning |
0 |
Disabled |
1 |
MinChannel |
2 |
MidChannel |
3 |
MaxChannel |
4 |
MinChannelCW |
5 |
MidChannelCW |
6 |
MaxChannelCW |
|
BRD_RADIO_TESTCH: Set radio to factory test channel
Note: This parameter is for advanced users
This sets the radio to a fixed test channel for factory testing. Using a fixed channel avoids the need for binding in factory testing.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
TestChan1 |
2 |
TestChan2 |
3 |
TestChan3 |
4 |
TestChan4 |
5 |
TestChan5 |
6 |
TestChan6 |
7 |
TestChan7 |
8 |
TestChan8 |
|
BRD_RADIO_TPPSCH: Telemetry PPS channel
Note: This parameter is for advanced users
Channel to show telemetry packets-per-second value, as received at TX
BRD_RADIO_TXMAX: Transmitter transmit power
Note: This parameter is for advanced users
Set transmitter maximum transmit power (from 1 to 8)
BRD_RADIO_BZOFS: Transmitter buzzer adjustment
Note: This parameter is for advanced users
Set transmitter buzzer note adjustment (adjust frequency up)
BRD_RADIO_ABTIME: Auto-bind time
Note: This parameter is for advanced users
When non-zero this sets the time with no transmitter packets before we start looking for auto-bind packets.
BRD_RADIO_ABLVL: Auto-bind level
Note: This parameter is for advanced users
This sets the minimum RSSI of an auto-bind packet for it to be accepted. This should be set so that auto-bind will only happen at short range to minimise the change of an auto-bind happening accidentially
BTN_ Parameters
BTN_REPORT_SEND: Report send time
The duration in seconds that a BUTTON_CHANGE report is repeatedly sent to the GCS regarding a button changing state. Note that the BUTTON_CHANGE message is MAVLink2 only.
CAM_ Parameters
CAM_TRIGG_TYPE: Camera shutter (trigger) type
how to trigger the camera to take a picture
Values |
Value |
Meaning |
0 |
Servo |
1 |
Relay |
2 |
GoPro in Solo Gimbal |
|
CAM_DURATION: Duration that shutter is held open
How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds)
Range |
Units |
0 - 50 |
deciseconds |
CAM_SERVO_ON: Servo ON PWM value
PWM value in microseconds to move servo to when shutter is activated
Range |
Units |
1000 - 2000 |
PWM in microseconds |
CAM_SERVO_OFF: Servo OFF PWM value
PWM value in microseconds to move servo to when shutter is deactivated
Range |
Units |
1000 - 2000 |
PWM in microseconds |
CAM_TRIGG_DIST: Camera trigger distance
Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
Range |
Units |
0 - 1000 |
meters |
CAM_RELAY_ON: Relay ON value
This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
Values |
Value |
Meaning |
0 |
Low |
1 |
High |
|
CAM_MIN_INTERVAL: Minimum time between photos
Postpone shooting if previous picture was taken less than preset time(ms) ago.
Range |
Units |
0 - 10000 |
milliseconds |
CAM_MAX_ROLL: Maximum photo roll angle.
Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
Range |
Units |
0 - 180 |
degrees |
CAM_FEEDBACK_PIN: Camera feedback pin
Note: Reboot required after change
pin number to use for save accurate camera feedback messages. If set to -1 then don’t use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. Some common values are given, but see the Wiki’s “GPIOs” page for how to determine the pin number for a given autopilot. See also the CAM_FEEDBACK_POL option.
Values |
Value |
Meaning |
-1 |
Disabled |
50 |
AUX1 |
51 |
AUX2 |
52 |
AUX3 |
53 |
AUX4 |
54 |
AUX5 |
55 |
AUX6 |
|
CAM_FEEDBACK_POL: Camera feedback pin polarity
Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
Values |
Value |
Meaning |
0 |
TriggerLow |
1 |
TriggerHigh |
|
CAM_AUTO_ONLY: Distance-trigging in AUTO mode only
When enabled, trigging by distance is done in AUTO mode only.
Values |
Value |
Meaning |
0 |
Always |
1 |
Only when in AUTO |
|
CAM_TYPE: Type of camera (0: None, 1: BMMCC)
Set the camera type that is being used, certain cameras have custom functions that need further configuration, this enables that.
Values |
Value |
Meaning |
0 |
Default |
1 |
BMMCC |
|
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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Increment |
Range |
Units |
1 |
-400 - 400 |
milligauss |
COMPASS_DEC: Compass declination
An angle to compensate between the true north and magnetic north
Increment |
Range |
Units |
0.01 |
-3.142 - 3.142 |
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.
Calibration |
Values |
1 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
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. The label for each option is specified in the order of rotations for that orientation.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Yaw45Roll180 |
10 |
Yaw90Roll180 |
11 |
Yaw135Roll180 |
12 |
Pitch180 |
13 |
Yaw225Roll180 |
14 |
Yaw270Roll180 |
15 |
Yaw315Roll180 |
16 |
Roll90 |
17 |
Yaw45Roll90 |
18 |
Yaw90Roll90 |
19 |
Yaw135Roll90 |
20 |
Roll270 |
21 |
Yaw45Roll270 |
22 |
Yaw90Roll270 |
23 |
Yaw135Roll270 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Yaw90Pitch180 |
27 |
Yaw270Pitch180 |
28 |
Pitch90Roll90 |
29 |
Pitch90Roll180 |
30 |
Pitch90Roll270 |
31 |
Pitch180Roll90 |
32 |
Pitch180Roll270 |
33 |
Pitch270Roll90 |
34 |
Pitch270Roll180 |
35 |
Pitch270Roll270 |
36 |
Yaw90Pitch180Roll90 |
37 |
Yaw270Roll90 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Pitch315Roll90 |
42 |
Roll45 |
43 |
Roll315 |
100 |
Custom 4.1 and older |
101 |
Custom 1 |
102 |
Custom 2 |
|
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 most boards. 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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Increment |
Range |
Units |
1 |
-400 - 400 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
milligauss per ampere |
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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
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
Increment |
Range |
Units |
1 |
-400 - 400 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
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)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
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 secondary 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 |
Yaw45Roll180 |
10 |
Yaw90Roll180 |
11 |
Yaw135Roll180 |
12 |
Pitch180 |
13 |
Yaw225Roll180 |
14 |
Yaw270Roll180 |
15 |
Yaw315Roll180 |
16 |
Roll90 |
17 |
Yaw45Roll90 |
18 |
Yaw90Roll90 |
19 |
Yaw135Roll90 |
20 | |