Complete Parameter List¶
Full Parameter List of Blimp latest V4.5.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.
Blimp Parameters¶
FORMAT_VERSION: Eeprom format version number¶
This value is incremented when changes are made to the eeprom format
SYSID_THISMAV: MAVLink system ID of this vehicle¶
Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
Range |
---|
1 to 255 |
SYSID_MYGCS: My ground station number¶
Allows restricting radio overrides to only come from my ground station
Increment |
Range |
---|---|
1 |
1 to 255 |
PILOT_THR_FILT: Throttle filter cutoff¶
Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
Increment |
Range |
Units |
---|---|---|
.5 |
0 to 10 |
hertz |
PILOT_THR_BHV: Throttle stick behavior¶
Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
TELEM_DELAY: Telemetry startup delay¶
The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
Increment |
Range |
Units |
---|---|---|
1 |
0 to 30 |
seconds |
GCS_PID_MASK: GCS PID tuning mask¶
bitmask of PIDs to send MAVLink PID_TUNING messages for
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FS_GCS_ENABLE: Ground Station Failsafe Enable¶
Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
Values |
||||||
---|---|---|---|---|---|---|
|
GPS_HDOP_GOOD: GPS Hdop Good¶
GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
Range |
---|
100 to 900 |
FS_THR_ENABLE: Throttle Failsafe Enable¶
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
Values |
||||||
---|---|---|---|---|---|---|
|
FS_THR_VALUE: Throttle Failsafe Value¶
The PWM level in microseconds on channel 3 below which throttle failsafe triggers
Increment |
Range |
Units |
---|---|---|
1 |
910 to 1100 |
PWM in microseconds |
THR_DZ: Throttle deadzone¶
The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
Increment |
Range |
Units |
---|---|---|
1 |
0 to 300 |
PWM in microseconds |
FLTMODE1: Flight Mode 1¶
Flight mode when Channel 5 pwm is <= 1230
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE2: Flight Mode 2¶
Flight mode when Channel 5 pwm is >1230, <= 1360
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE3: Flight Mode 3¶
Flight mode when Channel 5 pwm is >1360, <= 1490
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE4: Flight Mode 4¶
Flight mode when Channel 5 pwm is >1490, <= 1620
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE5: Flight Mode 5¶
Flight mode when Channel 5 pwm is >1620, <= 1749
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE6: Flight Mode 6¶
Flight mode when Channel 5 pwm is >=1750
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE_CH: Flightmode channel¶
RC Channel to use for flight mode control
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
INITIAL_MODE: Initial flight mode¶
This selects the mode to start in on boot.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
LOG_BITMASK: Log bitmask¶
Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535.
Bitmask |
||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
DISARM_DELAY: Disarm delay¶
Delay before automatic disarm in seconds. A value of zero disables auto disarm.
Range |
Units |
---|---|
0 to 127 |
seconds |
FS_EKF_ACTION: EKF Failsafe Action¶
Controls the action that will be taken when an EKF failsafe is invoked
Values |
||||||
---|---|---|---|---|---|---|
|
FS_EKF_THRESH: EKF failsafe variance threshold¶
Allows setting the maximum acceptable compass and velocity variance
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
FS_CRASH_CHECK: Crash check enable¶
This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
Values |
||||||
---|---|---|---|---|---|---|
|
MAX_VEL_XY: Max XY Velocity¶
Sets the maximum XY velocity, in m/s
Range |
---|
0.2 to 5 |
MAX_VEL_Z: Max Z Velocity¶
Sets the maximum Z velocity, in m/s
Range |
---|
0.2 to 5 |
MAX_VEL_YAW: Max yaw Velocity¶
Sets the maximum yaw velocity, in rad/s
Range |
---|
0.2 to 5 |
MAX_POS_XY: Max XY Position change¶
Sets the maximum XY position change, in m/s
Range |
---|
0.1 to 5 |
MAX_POS_Z: Max Z Position change¶
Sets the maximum Z position change, in m/s
Range |
---|
0.1 to 5 |
MAX_POS_YAW: Max Yaw Position change¶
Sets the maximum Yaw position change, in rad/s
Range |
---|
0.1 to 5 |
SIMPLE_MODE: Simple mode¶
Simple mode for Position control - "forward" moves blimp in +ve X direction world-frame
Values |
||||||
---|---|---|---|---|---|---|
|
DIS_MASK: Disable output mask¶
Mask for disabling (setting to zero) one or more of the 4 output axis in mode Velocity or Loiter
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
PID_DZ: Deadzone for the position PIDs¶
Output 0 thrust signal when blimp is within this distance (in meters) of the target position. Warning: If this param is greater than MAX_POS_XY param then the blimp won't move at all in the XY plane in Loiter mode as it does not allow more than a second's lag. Same for the other axes.
Range |
Units |
---|---|
0.1 to 1 |
meters |
RC_SPEED: ESC Update Speed¶
This is the speed in Hertz that your ESCs will receive updates
Increment |
Range |
Units |
---|---|---|
1 |
50 to 490 |
hertz |
VELXY_P: Velocity (horizontal) P gain¶
Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
VELXY_I: Velocity (horizontal) I gain¶
Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0.02 to 1.00 |
VELXY_D: Velocity (horizontal) D gain¶
Velocity (horizontal) D gain. Corrects short-term changes in velocity
Increment |
Range |
---|---|
0.001 |
0.00 to 1.00 |
VELXY_IMAX: Velocity (horizontal) integrator maximum¶
Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centimeters per square second |
VELXY_FLTE: Velocity (horizontal) input filter¶
Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
Range |
Units |
---|---|
0 to 100 |
hertz |
VELXY_FLTD: Velocity (horizontal) input filter¶
Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term
Range |
Units |
---|---|
0 to 100 |
hertz |
VELXY_FF: Velocity (horizontal) feed forward gain¶
Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0 to 6 |
VELZ_P: Velocity (vertical) P gain¶
Velocity (vertical) P gain. Converts the difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
VELZ_I: Velocity (vertical) I gain¶
Velocity (vertical) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0.02 to 1.00 |
VELZ_D: Velocity (vertical) D gain¶
Velocity (vertical) D gain. Corrects short-term changes in velocity
Increment |
Range |
---|---|
0.001 |
0.00 to 1.00 |
VELZ_IMAX: Velocity (vertical) integrator maximum¶
Velocity (vertical) integrator maximum. Constrains the target acceleration that the I gain will output
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centimeters per square second |
VELZ_FLTE: Velocity (vertical) input filter¶
Velocity (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
Range |
Units |
---|---|
0 to 100 |
hertz |
VELZ_FLTD: Velocity (vertical) input filter¶
Velocity (vertical) input filter. This filter (in Hz) is applied to the input for D term
Range |
Units |
---|---|
0 to 100 |
hertz |
VELZ_FF: Velocity (vertical) feed forward gain¶
Velocity (vertical) feed forward gain. Converts the difference between desired velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0 to 6 |
VELYAW_P: Velocity (yaw) P gain¶
Velocity (yaw) P gain. Converts the difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
VELYAW_I: Velocity (yaw) I gain¶
Velocity (yaw) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0.02 to 1.00 |
VELYAW_D: Velocity (yaw) D gain¶
Velocity (yaw) D gain. Corrects short-term changes in velocity
Increment |
Range |
---|---|
0.001 |
0.00 to 1.00 |
VELYAW_IMAX: Velocity (yaw) integrator maximum¶
Velocity (yaw) integrator maximum. Constrains the target acceleration that the I gain will output
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centimeters per square second |
VELYAW_FLTE: Velocity (yaw) input filter¶
Velocity (yaw) input filter. This filter (in Hz) is applied to the input for P and I terms
Range |
Units |
---|---|
0 to 100 |
hertz |
VELYAW_FF: Velocity (yaw) feed forward gain¶
Velocity (yaw) feed forward gain. Converts the difference between desired velocity to a target acceleration
Increment |
Range |
---|---|
0.01 |
0 to 6 |
POSXY_P: Position (horizontal) P gain¶
Position (horizontal) P gain. Converts the difference between desired and actual position to a target velocity
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
POSXY_I: Position (horizontal) I gain¶
Position (horizontal) I gain. Corrects long-term difference between desired and actual position to a target velocity
Increment |
Range |
---|---|
0.01 |
0.02 to 1.00 |
POSXY_D: Position (horizontal) D gain¶
Position (horizontal) D gain. Corrects short-term changes in position
Increment |
Range |
---|---|
0.001 |
0.00 to 1.00 |
POSXY_IMAX: Position (horizontal) integrator maximum¶
Position (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centimeters per square second |
POSXY_FLTE: Position (horizontal) input filter¶
Position (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
Range |
Units |
---|---|
0 to 100 |
hertz |
POSXY_FLTD: Position (horizontal) input filter¶
Position (horizontal) input filter. This filter (in Hz) is applied to the input for D term
Range |
Units |
---|---|
0 to 100 |
hertz |
POSXY_FF: Position (horizontal) feed forward gain¶
Position (horizontal) feed forward gain. Converts the difference between desired position to a target velocity
Increment |
Range |
---|---|
0.01 |
0 to 6 |
POSZ_P: Position (vertical) P gain¶
Position (vertical) P gain. Converts the difference between desired and actual position to a target velocity
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
POSZ_I: Position (vertical) I gain¶
Position (vertical) I gain. Corrects long-term difference between desired and actual position to a target velocity
Increment |
Range |
---|---|
0.01 |
0.02 to 1.00 |
POSZ_D: Position (vertical) D gain¶
Position (vertical) D gain. Corrects short-term changes in position
Increment |
Range |
---|---|
0.001 |
0.00 to 1.00 |
POSZ_IMAX: Position (vertical) integrator maximum¶
Position (vertical) integrator maximum. Constrains the target acceleration that the I gain will output
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centimeters per square second |
POSZ_FLTE: Position (vertical) input filter¶
Position (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
Range |
Units |
---|---|
0 to 100 |
hertz |
POSZ_FLTD: Position (vertical) input filter¶
Position (vertical) input filter. This filter (in Hz) is applied to the input for D term
Range |
Units |
---|---|
0 to 100 |
hertz |
POSZ_FF: Position (vertical) feed forward gain¶
Position (vertical) feed forward gain. Converts the difference between desired position to a target velocity
Increment |
Range |
---|---|
0.01 |
0 to 6 |
POSYAW_P: Position (yaw) axis controller P gain¶
Position (yaw) axis controller P gain.
Increment |
Range |
---|---|
0.01 |
0.0 to 3.0 |
POSYAW_I: Position (yaw) axis controller I gain¶
Position (yaw) axis controller I gain.
Increment |
Range |
---|---|
0.01 |
0.0 to 3.0 |
POSYAW_IMAX: Position (yaw) axis controller I gain maximum¶
Position (yaw) axis controller I gain maximum.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4000 |
decipercent |
POSYAW_D: Position (yaw) axis controller D gain¶
Position (yaw) axis controller D gain.
Increment |
Range |
---|---|
0.001 |
0.001 to 0.1 |
POSYAW_FF: Position (yaw) axis controller feed forward¶
Position (yaw) axis controller feed forward
Increment |
Range |
---|---|
0.001 |
0 to 0.5 |
POSYAW_FLTT: Position (yaw) target frequency filter in Hz¶
Position (yaw) target frequency filter in Hz
Increment |
Range |
Units |
---|---|---|
1 |
1 to 50 |
hertz |
POSYAW_FLTE: Position (yaw) error frequency filter in Hz¶
Position (yaw) error frequency filter in Hz
Increment |
Range |
Units |
---|---|---|
1 |
1 to 100 |
hertz |
POSYAW_FLTD: Position (yaw) derivative input filter in Hz¶
Position (yaw) derivative input filter in Hz
Increment |
Range |
Units |
---|---|---|
1 |
1 to 100 |
hertz |
POSYAW_SMAX: Yaw slew rate limit¶
Sets an upper limit on the slew rate produced by the combined P and D gains.
Increment |
Range |
---|---|
0.5 |
0 to 200 |
POSYAW_PDMX: Position (yaw) axis controller PD sum maximum¶
Position (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 |
POSYAW_D_FF: Position (yaw) Derivative FeedForward Gain¶
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 |
POSYAW_NTF: Position (yaw) Target notch filter index¶
Position (yaw) Target notch filter index
Range |
---|
1 to 8 |
POSYAW_NEF: Position (yaw) Error notch filter index¶
Position (yaw) Error notch filter index
Range |
---|
1 to 8 |
DEV_OPTIONS: Development options¶
Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
Bitmask |
||||
---|---|---|---|---|
|
SYSID_ENFORCE: GCS sysid enforcement¶
This controls whether packets from other than the expected GCS system ID will be accepted
Values |
||||||
---|---|---|---|---|---|---|
|
FRAME_CLASS: Frame Class¶
Controls major frame class for blimp.
Values |
||||
---|---|---|---|---|
|
PILOT_SPEED_DN: Pilot maximum vertical speed descending¶
The maximum vertical descending velocity the pilot may request in cm/s
Increment |
Range |
Units |
---|---|---|
10 |
50 to 500 |
centimeters per second |
FS_VIBE_ENABLE: Vibration Failsafe enable¶
This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations
Values |
||||||
---|---|---|---|---|---|---|
|
FS_OPTIONS: Failsafe options bitmask¶
Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.
Bitmask |
||||
---|---|---|---|---|
|
FS_GCS_TIMEOUT: GCS failsafe timeout¶
Timeout before triggering the GCS failsafe
Increment |
Range |
Units |
---|---|---|
1 |
2 to 120 |
seconds |
AHRS_ Parameters¶
AHRS_GPS_GAIN: AHRS GPS gain¶
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_YAW_P: Yaw P¶
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¶
This controls how fast the accelerometers correct the attitude
Increment |
Range |
---|---|
.01 |
0.1 to 0.4 |
AHRS_WIND_MAX: Maximum wind¶
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¶
Not Used
Increment |
Range |
Units |
---|---|---|
0.01 |
-0.1745 to +0.1745 |
radians |
AHRS_ORIENTATION: Board Orientation¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AHRS_COMP_BETA: AHRS Velocity Complementary Filter Beta Coefficient¶
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¶
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_CUSTOM_ROLL: Board orientation roll offset¶
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¶
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¶
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¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
AIS_ Parameters¶
AIS_TYPE: AIS receiver type¶
AIS receiver type
Values |
||||||
---|---|---|---|---|---|---|
|
AIS_LIST_MAX: AIS vessel list size¶
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¶
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¶
Bitmask of AIS logging options
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARMING_ Parameters¶
ARMING_ACCTHRESH: Accelerometer error threshold¶
Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
Range |
Units |
---|---|
0.25 to 3.0 |
meters per square second |
ARMING_RUDDER: Arming with Rudder enable/disable¶
Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode!
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARMING_MIS_ITEMS: Required mission items¶
Bitmask of mission items that are required to be planned in order to arm the aircraft
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARMING_CHECK: Arm Checks to Perform (bitmask)¶
Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. For most users it is recommended to leave this at the default of 1 (all checks enabled). You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72.
Bitmask |
||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARMING_OPTIONS: Arming options¶
Options that can be applied to change arming behaviour
Bitmask |
||||||
---|---|---|---|---|---|---|
|
ARMING_MAGTHRESH: Compass magnetic field strength error threshold vs earth magnetic model¶
Compass magnetic field strength error threshold vs earth magnetic model. X and y axis are compared using this threhold, Z axis uses 2x this threshold. 0 to disable check
Range |
Units |
---|---|
0 to 500 |
milligauss |
ARMING_CRSDP_IGN: Disable CrashDump Arming check¶
Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details.
Values |
||||||
---|---|---|---|---|---|---|
|
ARSPD Parameters¶
ARSPD_ENABLE: Airspeed Enable¶
Enable airspeed sensor support
Values |
||||||
---|---|---|---|---|---|---|
|
ARSPD_TUBE_ORDER: Control pitot tube order¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD_PRIMARY: Primary airspeed sensor¶
This selects which airspeed sensor will be the primary if multiple sensors are found
Values |
||||||
---|---|---|---|---|---|---|
|
ARSPD_OPTIONS: Airspeed options bitmask¶
This parameter and function is not used by this vehicle. Always set to 0.
Bitmask |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARSPD_WIND_MAX: Maximum airspeed and ground speed difference¶
This parameter and function is not used by this vehicle. Always set to 0.
Units |
---|
meters per second |
ARSPD_WIND_WARN: Airspeed and GPS speed difference that gives a warning¶
This parameter and function is not used by this vehicle. Always set to 0.
Units |
---|
meters per second |
ARSPD_WIND_GATE: Re-enable Consistency Check Gate Size¶
This parameter and function is not used by this vehicle.
Range |
---|
0.0 to 10.0 |
ARSPD_OFF_PCNT: Maximum offset cal speed error¶
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 ASPD_FBW_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 |
||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARSPD2_USE: Airspeed use¶
This parameter is not used by this vehicle. Always set to 0.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD2_OFFSET: Airspeed offset¶
Airspeed calibration offset
Increment |
---|
0.1 |
ARSPD2_RATIO: Airspeed ratio¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARSPD2_AUTOCAL: This parameter and function is not used by this vehicle. Always set to 0.¶
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¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD2_SKIP_CAL: Skip airspeed offset calibration on startup¶
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 |
||||||
---|---|---|---|---|---|---|
|
ARSPD2_PSI_RANGE: The PSI range of the device¶
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¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD2_DEVID: Airspeed ID¶
Airspeed sensor ID, taking into account its type, bus and instance
ReadOnly |
---|
True |
ARSPD_ Parameters¶
ARSPD_TYPE: Airspeed type¶
Type of airspeed sensor
Values |
||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARSPD_USE: Airspeed use¶
This parameter is not used by this vehicle. Always set to 0.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD_OFFSET: Airspeed offset¶
Airspeed calibration offset
Increment |
---|
0.1 |
ARSPD_RATIO: Airspeed ratio¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARSPD_AUTOCAL: This parameter and function is not used by this vehicle. Always set to 0.¶
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¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD_SKIP_CAL: Skip airspeed offset calibration on startup¶
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 |
||||||
---|---|---|---|---|---|---|
|
ARSPD_PSI_RANGE: The PSI range of the device¶
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¶
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARSPD_DEVID: Airspeed ID¶
Airspeed sensor ID, taking into account its type, bus and instance
ReadOnly |
---|
True |
BARO Parameters¶
BARO1_GND_PRESS: Ground Pressure¶
calibrated ground pressure in Pascals
Increment |
ReadOnly |
Units |
Volatile |
---|---|---|---|
1 |
True |
pascal |
True |
BARO_GND_TEMP: ground temperature¶
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¶
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¶
This selects which barometer will be the primary if multiple barometers are found
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BARO_EXT_BUS: External baro bus¶
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 |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
BARO2_GND_PRESS: Ground Pressure¶
calibrated ground pressure in Pascals
Increment |
ReadOnly |
Units |
Volatile |
---|---|---|---|
1 |
True |
pascal |
True |
BARO3_GND_PRESS: Absolute Pressure¶
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¶
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 |
||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BARO1_DEVID: Baro ID¶
Barometer sensor ID, taking into account its type, bus and instance
ReadOnly |
---|
True |
BARO2_DEVID: Baro ID2¶
Barometer2 sensor ID, taking into account its type, bus and instance
ReadOnly |
---|
True |
BARO3_DEVID: Baro ID3¶
Barometer3 sensor ID, taking into account its type, bus and instance
ReadOnly |
---|
True |
BARO_FIELD_ELV: field elevation¶
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¶
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¶
Barometer options
Bitmask |
||||
---|---|---|---|---|
|
BARO1_WCF_ Parameters¶
BARO1_WCF_ENABLE: Wind coefficient enable¶
This enables the use of wind coefficients for barometer compensation
Values |
||||||
---|---|---|---|---|---|---|
|
BARO1_WCF_FWD: Pressure error coefficient in positive X direction (forward)¶
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)¶
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)¶
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)¶
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)¶
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)¶
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¶
This enables the use of wind coefficients for barometer compensation
Values |
||||||
---|---|---|---|---|---|---|
|
BARO2_WCF_FWD: Pressure error coefficient in positive X direction (forward)¶
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)¶
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)¶
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)¶
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)¶
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)¶
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¶
This enables the use of wind coefficients for barometer compensation
Values |
||||||
---|---|---|---|---|---|---|
|
BARO3_WCF_FWD: Pressure error coefficient in positive X direction (forward)¶
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)¶
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)¶
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)¶
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)¶
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)¶
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¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT2_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT2_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT2_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT2_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT2_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT2_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT2_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT2_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT2_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT2_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_ Parameters¶
BATT3_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT3_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT3_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT3_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT3_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT3_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT3_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT3_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT3_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT3_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT3_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_ Parameters¶
BATT4_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT4_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT4_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT4_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT4_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT4_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT4_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT4_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT4_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT4_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT4_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_ Parameters¶
BATT5_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT5_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT5_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT5_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT5_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT5_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT5_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT5_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT5_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT5_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT5_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_ Parameters¶
BATT6_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT6_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT6_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT6_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT6_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT6_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT6_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT6_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT6_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT6_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT6_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_ Parameters¶
BATT7_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT7_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT7_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT7_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT7_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT7_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT7_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT7_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT7_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT7_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT7_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_ Parameters¶
BATT8_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT8_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT8_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT8_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT8_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT8_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT8_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT8_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT8_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT8_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT8_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_ Parameters¶
BATT9_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT9_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATT9_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATT9_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT9_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATT9_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATT9_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATT9_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATT9_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT9_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATT9_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_ Parameters¶
BATTA_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTA_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTA_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTA_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTA_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTA_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTA_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTA_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTA_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTA_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTA_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTA_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_ Parameters¶
BATTB_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTB_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTB_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTB_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTB_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTB_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTB_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTB_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTB_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTB_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTB_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTB_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_ Parameters¶
BATTC_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTC_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTC_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTC_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTC_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTC_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTC_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTC_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTC_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTC_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTC_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTC_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_ Parameters¶
BATTD_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTD_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTD_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTD_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTD_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTD_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTD_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTD_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTD_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTD_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTD_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTD_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_ Parameters¶
BATTE_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTE_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTE_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTE_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_VOLT_MULT: Voltage Multiplier¶
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¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTE_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_CURR_MULT: Scales reported power monitor current¶
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¶
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¶
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¶
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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTE_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTE_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTE_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTE_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTE_MAX_VOLT: Maximum Battery Voltage¶
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¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTE_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
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¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTE_SHUNT: Battery monitor shunt resistor¶
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 |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_ Parameters¶
BATTF_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATTF_SERIAL_NUM: Battery serial number¶
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¶
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¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
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 |
||||||
---|---|---|---|---|---|---|
|
BATTF_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||
---|---|---|---|---|---|---|
|
BATTF_ARM_VOLT: Required arming voltage¶
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¶
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¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_ESC_INDEX: ESC Telemetry Index to write to¶
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¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_VOLT_MULT: Voltage Multiplier¶
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¶
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 |
BATTF_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTF_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATTF_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 |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_CURR_MULT: Scales reported power monitor current¶
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
Range |
---|
.1 to 10 |
BATTF_FL_VLT_MIN: Empty fuel level voltage¶
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 |
BATTF_FL_V_MULT: Fuel level voltage multiplier¶
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 |
BATTF_FL_FLTR: Fuel level filter frequency¶
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 |
BATTF_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 |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATTF_FL_FF: First order term¶
First order polynomial fit term
Range |
---|
0 to 10 |
BATTF_FL_FS: Second order term¶
Second order polynomial fit term
Range |
---|
0 to 10 |
BATTF_FL_FT: Third order term¶
Third order polynomial fit term
Range |
---|
0 to 10 |
BATTF_FL_OFF: Offset term¶
Offset polynomial fit term
Range |
---|
0 to 10 |
BATTF_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATTF_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATTF_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address¶
Battery monitor I2C address. If this is zero then probe list of supported addresses
Range |
---|
0 to 127 |
BATTF_MAX_AMPS: Battery monitor max current¶
This controls the maximum current the INS2XX sensor will work with.
Range |
Units |
---|---|
1 to 400 |
ampere |
BATTF_SHUNT: Battery monitor shunt resistor¶
This sets the shunt resistor used in the device
Range |
Units |
---|---|
0.0001 to 0.01 |
Ohm |
BATTF_ESC_MASK: ESC mask¶
If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|