Complete Parameter List

Full Parameter List of AntennaTracker latest V4.7.0 dev

You can change and check the parameters for another version:

This is a complete list of the parameters which can be set (e.g. via the MAVLink protocol) to control vehicle behaviour. They are stored in persistent storage on the vehicle.

This list is automatically generated from the latest ardupilot source code, and so may contain parameters which are not yet in the stable released versions of the code.

AntennaTracker Parameters

FORMAT_VERSION: Eeprom format version number

Note: This parameter is for advanced users

This value is incremented when changes are made to the eeprom format

YAW_SLEW_TIME: Time for yaw to slew through its full range

This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.

Increment

Range

Units

0.1

0 to 20

seconds

PITCH_SLEW_TIME: Time for pitch to slew through its full range

This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.

Increment

Range

Units

0.1

0 to 20

seconds

MIN_REVERSE_TIME: Minimum time to apply a yaw reversal

When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.

Increment

Range

Units

1

0 to 20

seconds

START_LATITUDE: Initial Latitude before GPS lock

Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.

Increment

Range

Units

0.000001

-90 to 90

degrees

START_LONGITUDE: Initial Longitude before GPS lock

Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.

Increment

Range

Units

0.000001

-180 to 180

degrees

STARTUP_DELAY: Delay before first servo movement from trim

This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types

Increment

Range

Units

0.1

0 to 10

seconds

SERVO_PITCH_TYPE: Type of servo system being used for pitch

This allows selection of position servos or on/off servos for pitch

Values

Value

Meaning

0

Position

1

OnOff

2

ContinuousRotation

SERVO_YAW_TYPE: Type of servo system being used for yaw

This allows selection of position servos or on/off servos for yaw

Values

Value

Meaning

0

Position

1

OnOff

2

ContinuousRotation

ONOFF_YAW_RATE: Yaw rate for on/off servos

Rate of change of yaw in degrees/second for on/off servos

Increment

Range

Units

0.1

0 to 50

degrees per second

ONOFF_PITCH_RATE: Pitch rate for on/off servos

Rate of change of pitch in degrees/second for on/off servos

Increment

Range

Units

0.1

0 to 50

degrees per second

ONOFF_YAW_MINT: Yaw minimum movement time

Minimum amount of time in seconds to move in yaw

Increment

Range

Units

0.01

0 to 2

seconds

ONOFF_PITCH_MINT: Pitch minimum movement time

Minimum amount of time in seconds to move in pitch

Increment

Range

Units

0.01

0 to 2

seconds

YAW_TRIM: Yaw trim

Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.

Increment

Range

Units

0.1

-10 to 10

degrees

PITCH_TRIM: Pitch trim

Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.

Increment

Range

Units

0.1

-10 to 10

degrees

YAW_RANGE: Yaw Angle Range

Yaw axis total range of motion in degrees

Increment

Range

Units

0.1

0 to 360

degrees

DISTANCE_MIN: Distance minimum to target

Tracker will track targets at least this distance away

Increment

Range

Units

1

0 to 100

meters

ALT_SOURCE: Altitude Source

What provides altitude information for vehicle. Vehicle only assumes tracker has same altitude as vehicle's home

Values

Value

Meaning

0

Barometer

1

GPS

2

GPS vehicle only

PITCH_MIN: Minimum Pitch Angle

The lowest angle the pitch can reach

Increment

Range

Units

1

-90 to 0

degrees

PITCH_MAX: Maximum Pitch Angle

The highest angle the pitch can reach

Increment

Range

Units

1

0 to 90

degrees

LOG_BITMASK: Log bitmask

4 byte bitmap of log types to enable

Bitmask

Bit

Meaning

0

ATTITUDE

1

GPS

2

RCIN

3

IMU

4

RCOUT

5

COMPASS

6

Battery

PITCH2SRV_P: Pitch axis controller P gain

Pitch axis controller P gain. Converts the difference between desired pitch angle and actual pitch angle into a pitch servo pwm change

Increment

Range

0.01

0.0 to 3.0

PITCH2SRV_I: Pitch axis controller I gain

Pitch axis controller I gain. Corrects long-term difference in desired pitch angle vs actual pitch angle

Increment

Range

0.01

0.0 to 3.0

PITCH2SRV_IMAX: Pitch axis controller I gain maximum

Pitch axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output

Increment

Range

Units

10

0 to 4000

decipercent

PITCH2SRV_D: Pitch axis controller D gain

Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle

Increment

Range

0.001

0.001 to 0.1

PITCH2SRV_FF: Pitch axis controller feed forward

Pitch axis controller feed forward

Increment

Range

0.001

0 to 0.5

PITCH2SRV_FLTT: Pitch axis controller target frequency in Hz

Pitch axis controller target frequency in Hz

Increment

Range

Units

1

1 to 50

hertz

PITCH2SRV_FLTE: Pitch axis controller error frequency in Hz

Pitch axis controller error frequency in Hz

Increment

Range

Units

1

1 to 100

hertz

PITCH2SRV_FLTD: Pitch axis controller derivative frequency in Hz

Pitch axis controller derivative frequency in Hz

Increment

Range

Units

1

1 to 100

hertz

PITCH2SRV_SMAX: Pitch 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 to 200

PITCH2SRV_PDMX: Pitch axis controller PD sum maximum

Note: This parameter is for advanced users

Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output

Increment

Range

Units

10

0 to 4000

decipercent

PITCH2SRV_D_FF: Pitch Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.001

0 to 0.1

PITCH2SRV_NTF: Pitch Target notch filter index

Note: This parameter is for advanced users

Pitch Target notch filter index

Range

1 to 8

PITCH2SRV_NEF: Pitch Error notch filter index

Note: This parameter is for advanced users

Pitch Error notch filter index

Range

1 to 8

YAW2SRV_P: Yaw axis controller P gain

Yaw axis controller P gain. Converts the difference between desired yaw angle (heading) and actual yaw angle into a yaw servo pwm change

Increment

Range

0.01

0.0 to 3.0

YAW2SRV_I: Yaw axis controller I gain

Yaw axis controller I gain. Corrects long-term difference in desired yaw angle (heading) vs actual yaw angle

Increment

Range

0.01

0.0 to 3.0

YAW2SRV_IMAX: Yaw axis controller I gain maximum

Yaw axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output

Increment

Range

Units

10

0 to 4000

decipercent

YAW2SRV_D: Yaw axis controller D gain

Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle

Increment

Range

0.001

0.001 to 0.1

YAW2SRV_FF: Yaw axis controller feed forward

Yaw axis controller feed forward

Increment

Range

0.001

0 to 0.5

YAW2SRV_FLTT: Yaw axis controller target frequency in Hz

Yaw axis controller target frequency in Hz

Increment

Range

Units

1

1 to 50

hertz

YAW2SRV_FLTE: Yaw axis controller error frequency in Hz

Yaw axis controller error frequency in Hz

Increment

Range

Units

1

1 to 100

hertz

YAW2SRV_FLTD: Yaw axis controller derivative frequency in Hz

Yaw axis controller derivative frequency in Hz

Increment

Range

Units

1

1 to 100

hertz

YAW2SRV_SMAX: Yaw 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 to 200

YAW2SRV_PDMX: Yaw axis controller PD sum maximum

Note: This parameter is for advanced users

Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output

Increment

Range

Units

10

0 to 4000

decipercent

YAW2SRV_D_FF: Yaw Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.001

0 to 0.1

YAW2SRV_NTF: Yaw Target notch filter index

Note: This parameter is for advanced users

Yaw Target notch filter index

Range

1 to 8

YAW2SRV_NEF: Yaw Error notch filter index

Note: This parameter is for advanced users

Yaw Error notch filter index

Range

1 to 8

CMD_TOTAL: Number of loaded mission items

Note: This parameter is for advanced users

Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.

Range

1 to 255

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

Bit

Meaning

0

Pitch

1

Yaw

SCAN_SPEED_YAW: Speed at which to rotate the yaw axis in scan mode

This controls how rapidly the tracker will move the servos in SCAN mode

Increment

Range

Units

1

0 to 100

degrees per second

SCAN_SPEED_PIT: Speed at which to rotate pitch axis in scan mode

This controls how rapidly the tracker will move the servos in SCAN mode

Increment

Range

Units

1

0 to 100

degrees per second

INITIAL_MODE: Mode tracker will switch into after initialization

0:MANUAL, 1:STOP, 2:SCAN, 10:AUTO

SAFE_DISARM_PWM: PWM that will be output when disarmed or in stop mode

0:zero pwm, 1:trim pwm

AUTO_OPTIONS: Auto mode options

1: Scan for unknown target

Bitmask

Bit

Meaning

0

Scan for unknown target

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 to 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 to 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 to 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. A value of zero means to use the airspeed as is. This allows the plane to cope with a failing airspeed sensor by clipping it to groundspeed plus/minus this limit. See ARSPD_OPTIONS and ARSPD_WIND_MAX to disable airspeed sensors.

Increment

Range

Units

1

0 to 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 to +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 to +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 to +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. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the AHRS_CUSTOM_ROLL/PIT/YAW angles for AHRS orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_ROT1_ROLL/PIT/YAW or CUST_ROT2_ROLL/PIT/YAW angles.

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

Increment

Range

1

0 to 10

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 to 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 to 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 to 180

degrees

AHRS_OPTIONS: Optional AHRS behaviour

Note: This parameter is for advanced users

This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. Setting DontDisableAirspeedUsingEKF disables the EKF based innovation check for airspeed consistency

Bitmask

Bit

Meaning

0

DisableDCMFallbackFW

1

DisableDCMFallbackVTOL

2

DontDisableAirspeedUsingEKF

AIS_ Parameters

AIS_TYPE: AIS receiver type

Note: Reboot required after change

AIS receiver type

Values

Value

Meaning

0

None

1

NMEA AIVDM message

AIS_LIST_MAX: AIS vessel list size

Note: This parameter is for advanced users

AIS list size of nearest vessels. Longer lists take longer to refresh with lower SRx_ADSB values.

Range

1 to 100

AIS_TIME_OUT: AIS vessel time out

Note: This parameter is for advanced users

if no updates are received in this time a vessel will be removed from the list

Range

Units

1 to 2000

seconds

AIS_LOGGING: AIS logging options

Note: This parameter is for advanced users

Bitmask of AIS logging options

Bitmask

Bit

Meaning

0

Log all AIVDM messages

1

Log only unsupported AIVDM messages

2

Log decoded messages

ARSPD Parameters

ARSPD_ENABLE: Airspeed Enable

Enable airspeed sensor support

Values

Value

Meaning

0

Disable

1

Enable

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

Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3), 4:Report cal offset to GCS

Bitmask

Bit

Meaning

0

SpeedMismatchDisable

1

AllowSpeedMismatchRecovery

2

DisableVoltageCorrection

3

UseEkf3Consistency

4

ReportOffset

ARSPD_WIND_MAX: Maximum airspeed and ground speed difference

Note: This parameter is for advanced users

If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTION this health value can be used to disable the sensor.

Units

meters per second

ARSPD_WIND_WARN: Airspeed and GPS speed difference that gives a warning

Note: This parameter is for advanced users

If the difference between airspeed and GPS speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used.

Units

meters per second

ARSPD_WIND_GATE: Re-enable Consistency Check Gate Size

Note: This parameter is for advanced users

Number of standard deviations applied to the re-enable EKF consistency check that is used when ARSPD_OPTIONS bit position 3 is set. Larger values will make the re-enabling of the airspeed sensor faster, but increase the likelihood of re-enabling a degraded sensor. The value can be tuned by using the ARSP.TR log message by setting ARSPD_WIND_GATE to a value that is higher than the value for ARSP.TR observed with a healthy airspeed sensor. Occasional transients in ARSP.TR above the value set by ARSPD_WIND_GATE can be tolerated provided they are less than 5 seconds in duration and less than 10% duty cycle.

Range

0.0 to 10.0

ARSPD_OFF_PCNT: Maximum offset cal speed error

Note: This parameter is for advanced users

The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered.

Range

Units

0.0 to 10.0

percent

ARSPD2_ Parameters

ARSPD2_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

16

ExternalAHRS

100

SITL

ARSPD2_USE: Airspeed use

Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).

Values

Value

Meaning

0

DoNotUse

1

Use

2

UseWhenZeroThrottle

ARSPD2_OFFSET: Airspeed offset

Note: This parameter is for advanced users

Airspeed calibration offset

Increment

0.1

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

Increment

0.1

ARSPD2_PIN: Airspeed pin

Note: This parameter is for advanced users

The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

ARSPD2_AUTOCAL: Automatic airspeed ratio calibration

Note: This parameter is for advanced users

Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.

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

ARSPD2_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

ARSPD2_PSI_RANGE: The PSI range of the device

Note: This parameter is for advanced users

This parameter allows you 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

Note: This parameter is for advanced users
Note: Reboot required after change

Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.

Values

Value

Meaning

0

Bus0

1

Bus1

2

Bus2

ARSPD2_DEVID: Airspeed ID

Note: This parameter is for advanced users

Airspeed sensor ID, taking into account its type, bus and instance

ReadOnly

True

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

16

ExternalAHRS

100

SITL

ARSPD_USE: Airspeed use

Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).

Values

Value

Meaning

0

DoNotUse

1

Use

2

UseWhenZeroThrottle

ARSPD_OFFSET: Airspeed offset

Note: This parameter is for advanced users

Airspeed calibration offset

Increment

0.1

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.

Increment

0.1

ARSPD_PIN: Airspeed pin

Note: This parameter is for advanced users

The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

ARSPD_AUTOCAL: Automatic airspeed ratio calibration

Note: This parameter is for advanced users

Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.

ARSPD_TUBE_ORDR: 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 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
Note: Reboot required after change

Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.

Values

Value

Meaning

0

Bus0

1

Bus1

2

Bus2

ARSPD_DEVID: Airspeed ID

Note: This parameter is for advanced users

Airspeed sensor ID, taking into account its type, bus and instance

ReadOnly

True

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

Values

Value

Meaning

-1

Disabled

0

Bus0

1

Bus1

6

Bus6

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 to 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 BARO_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 BARO_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

13

BMP581

BARO1_DEVID: Baro ID

Note: This parameter is for advanced users

Barometer sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO2_DEVID: Baro ID2

Note: This parameter is for advanced users

Barometer2 sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO3_DEVID: Baro ID3

Note: This parameter is for advanced users

Barometer3 sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO_FIELD_ELV: field elevation

Note: This parameter is for advanced users

User provided field elevation in meters. 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. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level.

Increment

Units

Volatile

0.1

meters

True

BARO_ALTERR_MAX: Altitude error maximum

Note: This parameter is for advanced users

This is the maximum acceptable altitude discrepancy between GPS altitude and barometric presssure altitude calculated against a standard atmosphere for arming checks to pass. If you are getting an arming error due to this parameter then you may have a faulty or substituted barometer. A common issue is vendors replacing a MS5611 in a "Pixhawk" with a MS5607. If you have that issue then please see BARO_OPTIONS parameter to force the MS5611 to be treated as a MS5607. This check is disabled if the value is zero.

Increment

Range

Units

1

0 to 5000

meters

BARO_OPTIONS: Barometer options

Note: This parameter is for advanced users

Barometer options

Bitmask

Bit

Meaning

0

Treat MS5611 as MS5607

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 to 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 to 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 to 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 to 1.0

BARO1_WCF_UP: Pressure error coefficient in positive Z direction (up)

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 Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), 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 to 1.0

BARO1_WCF_DN: Pressure error coefficient in negative Z direction (down)

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 Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), 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 to 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 to 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 to 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 to 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 to 1.0

BARO2_WCF_UP: Pressure error coefficient in positive Z direction (up)

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 Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), 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 to 1.0

BARO2_WCF_DN: Pressure error coefficient in negative Z direction (down)

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 Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), 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 to 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 to 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 to 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 to 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 to 1.0

BARO3_WCF_UP: Pressure error coefficient in positive Z direction (up)

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 Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), 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 to 1.0

BARO3_WCF_DN: Pressure error coefficient in negative Z direction (down)

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 Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), 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 to 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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT2_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT2_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT2_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT2_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT2_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT2_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT2_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT2_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT2_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT2_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT2_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT2_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT2_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT2_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT2_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT2_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT2_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT3_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT3_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT3_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT3_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT3_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT3_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT3_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT3_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT3_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT3_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT3_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT3_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT3_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT3_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT3_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT3_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT3_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT4_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT4_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT4_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT4_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT4_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT4_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT4_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT4_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT4_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT4_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT4_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT4_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT4_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT4_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT4_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT4_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT4_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT5_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT5_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT5_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT5_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT5_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT5_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT5_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT5_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT5_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT5_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT5_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT5_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT5_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT5_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT5_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT5_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT5_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT6_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT6_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT6_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT6_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT6_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT6_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT6_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT6_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT6_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT6_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT6_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT6_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT6_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT6_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT6_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT6_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT6_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT7_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT7_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT7_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT7_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT7_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT7_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT7_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT7_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT7_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT7_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT7_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT7_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT7_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT7_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT7_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT7_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT7_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT8_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT8_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT8_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT8_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT8_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT8_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT8_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT8_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT8_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT8_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT8_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT8_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT8_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT8_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT8_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT8_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT8_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

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

Increment

Units

0.1

volt

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.

Increment

Units

0.1

volt

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

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

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.

Increment

Units

0.1

volt

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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT9_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT9_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATT9_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT9_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

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

Range

.1 to 10

BATT9_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT9_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT9_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT9_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT9_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT9_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT9_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT9_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT9_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT9_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT9_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT9_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT9_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTA_ Parameters

BATTA_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTA_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTA_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 to 120

seconds

BATTA_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

BATTA_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 BATTA_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTA_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTA_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 BATTA_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTA_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 BATTA_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTA_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTA_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 BATTA_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTA_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

BATTA_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

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

Increment

Units

0.1

volt

BATTA_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 BATTA_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTA_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTA_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTA_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

BATTA_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

BATTA_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTA_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.

BATTA_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTA_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATTA_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTA_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATTA_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

BATTA_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

Range

.1 to 10

BATTA_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATTA_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATTA_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATTA_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

BATTA_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATTA_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATTA_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATTA_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATTA_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATTA_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTA_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATTA_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATTA_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATTA_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTB_ Parameters

BATTB_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTB_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTB_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 to 120

seconds

BATTB_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

BATTB_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 BATTB_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTB_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTB_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 BATTB_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTB_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 BATTB_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTB_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTB_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 BATTB_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTB_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

BATTB_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

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

Increment

Units

0.1

volt

BATTB_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 BATTB_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTB_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTB_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTB_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

BATTB_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

BATTB_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTB_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.

BATTB_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTB_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATTB_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTB_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATTB_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

BATTB_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

Range

.1 to 10

BATTB_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATTB_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATTB_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATTB_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

BATTB_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATTB_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATTB_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATTB_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATTB_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATTB_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTB_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATTB_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATTB_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATTB_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTC_ Parameters

BATTC_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTC_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTC_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 to 120

seconds

BATTC_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

BATTC_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 BATTC_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTC_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTC_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 BATTC_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTC_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 BATTC_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTC_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTC_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 BATTC_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTC_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

BATTC_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

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

Increment

Units

0.1

volt

BATTC_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 BATTC_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTC_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTC_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTC_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

BATTC_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

BATTC_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTC_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.

BATTC_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTC_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATTC_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTC_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATTC_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

BATTC_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

Range

.1 to 10

BATTC_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATTC_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATTC_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATTC_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

BATTC_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATTC_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATTC_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATTC_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATTC_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATTC_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTC_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATTC_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATTC_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATTC_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTD_ Parameters

BATTD_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTD_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTD_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 to 120

seconds

BATTD_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

BATTD_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 BATTD_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTD_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTD_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 BATTD_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTD_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 BATTD_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTD_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTD_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 BATTD_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTD_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

BATTD_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

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

Increment

Units

0.1

volt

BATTD_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 BATTD_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTD_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTD_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTD_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

BATTD_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

BATTD_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTD_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.

BATTD_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTD_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATTD_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTD_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATTD_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

BATTD_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

Range

.1 to 10

BATTD_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATTD_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATTD_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATTD_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

BATTD_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATTD_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATTD_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATTD_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATTD_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATTD_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTD_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATTD_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATTD_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATTD_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTE_ Parameters

BATTE_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTE_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTE_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 to 120

seconds

BATTE_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

BATTE_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 BATTE_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTE_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTE_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 BATTE_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTE_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 BATTE_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTE_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTE_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 BATTE_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTE_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

BATTE_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

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

Increment

Units

0.1

volt

BATTE_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 BATTE_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTE_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTE_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTE_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

BATTE_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

BATTE_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTE_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.

BATTE_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTE_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

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

Units

volt

BATTE_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTE_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATTE_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

BATTE_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

Range

.1 to 10

BATTE_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATTE_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATTE_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATTE_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

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

BATTE_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATTE_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATTE_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATTE_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATTE_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATTE_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATTE_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATTE_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATTE_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATTE_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATTF_ Parameters

BATTF_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

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATTF_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

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

BATTF_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 to 120

seconds

BATTF_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

BATTF_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 BATTF_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTF_FS_LOW_ACT parameter.

Increment

Units

0.1

volt

BATTF_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 BATTF_FS_LOW_ACT parameter.

Increment

Units

50

milliampere hour

BATTF_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 BATTF_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATTF_FS_CRT_ACT parameter.

Increment

Units

0.1

volt

BATTF_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 BATTF_FS_CRT_ACT parameter.

Increment

Units

50

milliampere hour

BATTF_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

BATTF_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

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

Increment

Units

0.1

volt

BATTF_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 BATTF_ARM_VOLT parameter.

Increment

Units

50

milliampere hour

BATTF_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

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATTF_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATTF_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

BATTF_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

BATTF_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

Used to convert the voltage of the voltage sensing pin (BATTF_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.

BATTF_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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATTF_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

BATTF_VLT_OFFSET: Voltage offset