Complete Parameter List¶
Full Parameter List of Rover latest V4.6.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.
Rover Parameters¶
FORMAT_VERSION: Eeprom format version number¶
This value is incremented when changes are made to the eeprom format
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 |
||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
RST_SWITCH_CH: Reset Switch Channel¶
RC channel to use to reset to last flight mode after geofence takeover.
INITIAL_MODE: Initial driving mode¶
This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
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: MAVLink ground station ID¶
The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
Increment |
Range |
---|---|
1 |
1 to 255 |
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 |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AUTO_TRIGGER_PIN: Auto mode trigger pin¶
pin number to use to enable the throttle in auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver.
Values |
||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AUTO_KICKSTART: Auto mode trigger kickstart acceleration¶
X acceleration in meters/second/second to use to trigger the motor start in auto mode. If set to zero then auto throttle starts immediately when the mode switch happens, otherwise the rover waits for the X acceleration to go above this value before it will start the motor
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 20 |
meters per square second |
CRUISE_SPEED: Target cruise speed in auto modes¶
The target speed in auto missions.
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 100 |
meters per second |
CRUISE_THROTTLE: Base throttle percentage in auto¶
The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 100 |
percent |
PILOT_STEER_TYPE: Pilot input steering type¶
Pilot RC input interpretation
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
FS_ACTION: Failsafe Action¶
What to do on a failsafe event
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FS_TIMEOUT: Failsafe timeout¶
The time in seconds that a failsafe condition must persist before the failsafe action is triggered
Increment |
Range |
Units |
---|---|---|
0.5 |
1 to 100 |
seconds |
FS_THR_ENABLE: Throttle Failsafe Enable¶
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range. Failsafe will be triggered when the throttle channel goes below the FS_THR_VALUE for FS_TIMEOUT seconds.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
FS_THR_VALUE: Throttle Failsafe Value¶
The PWM level on the throttle channel below which throttle failsafe triggers.
Increment |
Range |
---|---|
1 |
910 to 1100 |
FS_GCS_ENABLE: GCS failsafe enable¶
Enable ground control station telemetry failsafe. When enabled the Rover will execute the FS_ACTION when it fails to receive MAVLink heartbeat packets for FS_TIMEOUT seconds.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
FS_CRASH_CHECK: Crash check action¶
What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
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 |
||||||||
---|---|---|---|---|---|---|---|---|
|
MODE_CH: Mode channel¶
RC Channel to use for driving mode control
MODE1: Mode1¶
Driving mode for switch position 1 (910 to 1230 and above 2049)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
MODE2: Mode2¶
Driving mode for switch position 2 (1231 to 1360)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
MODE3: Mode3¶
Driving mode for switch position 3 (1361 to 1490)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
MODE4: Mode4¶
Driving mode for switch position 4 (1491 to 1620)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
MODE5: Mode5¶
Driving mode for switch position 5 (1621 to 1749)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
MODE6: Mode6¶
Driving mode for switch position 6 (1750 to 2049)
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
SYSID_ENFORCE: GCS sysid enforcement¶
This controls whether packets from other than the expected GCS system ID will be accepted
Values |
||||||
---|---|---|---|---|---|---|
|
TURN_RADIUS: Turn radius of vehicle¶
Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 10 |
meters |
ACRO_TURN_RATE: Acro mode turn rate maximum¶
Acro mode turn rate maximum
Increment |
Range |
Units |
---|---|---|
1 |
0 to 360 |
degrees per second |
RTL_SPEED: Return-to-Launch speed default¶
Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 100 |
meters per second |
FRAME_CLASS: Frame Class¶
Frame Class
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
BAL_PITCH_MAX: BalanceBot Maximum Pitch¶
Pitch angle in degrees at 100% throttle
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 15 |
degrees |
CRASH_ANGLE: Crash Angle¶
Pitch/Roll angle limit in degrees for crash check. Zero disables check
Increment |
Range |
Units |
---|---|---|
1 |
0 to 60 |
degrees |
FRAME_TYPE: Frame Type¶
Frame Type
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
LOIT_TYPE: Loiter type¶
Loiter behaviour when moving to the target point
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
SIMPLE_TYPE: Simple_Type¶
Simple mode types
Values |
||||||
---|---|---|---|---|---|---|
|
LOIT_RADIUS: Loiter radius¶
Vehicle will drift when within this distance of the target position
Increment |
Range |
Units |
---|---|---|
1 |
0 to 20 |
meters |
MIS_DONE_BEHAVE: Mission done behave¶
Behaviour after mission completes
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
BAL_PITCH_TRIM: Balance Bot pitch trim angle¶
Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
Increment |
Range |
Units |
---|---|---|
0.1 |
-2 to 2 |
degrees |
STICK_MIXING: Stick Mixing¶
When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
Values |
||||||
---|---|---|---|---|---|---|
|
SPEED_MAX: Speed maximum¶
Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 30 |
meters per second |
LOIT_SPEED_GAIN: Loiter speed gain¶
Determines how agressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.
Increment |
Range |
---|---|
0.01 |
0 to 5 |
FS_OPTIONS: Failsafe Options¶
Bitmask to enable failsafe options
Bitmask |
||||
---|---|---|---|---|
|
GUID_OPTIONS: Guided mode options¶
Options that can be applied to change guided mode behaviour
Bitmask |
||||
---|---|---|---|---|
|
MANUAL_OPTIONS: Manual mode options¶
Manual mode specific options
Bitmask |
||||
---|---|---|---|---|
|
MANUAL_STR_EXPO: Manual Steering Expo¶
Manual steering expo to allow faster steering when stick at edges
Range |
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
-0.5 to 0.95 |
|
FS_GCS_TIMEOUT: GCS failsafe timeout¶
Timeout before triggering the GCS failsafe
Increment |
Range |
Units |
---|---|---|
1 |
2 to 120 |
seconds |
CH7_OPTION: Channel 7 option¶
What to do use channel 7 for
Values |
||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AUX_CH: Auxiliary switch channel¶
RC Channel to use for auxiliary functions including saving waypoints
PIVOT_TURN_ANGLE: Pivot turn angle¶
Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 360 |
degrees |
PIVOT_TURN_RATE: Pivot turn rate¶
Desired pivot turn rate in deg/s.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 360 |
degrees per second |
VEHICLE Parameters¶
FLTMODE_GCSBLOCK: Flight mode block from GCS¶
Bitmask of flight modes to disable for GCS selection. Mode can still be accessed via RC or failsafe.
Bitmask |
||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AFS_ Parameters¶
AFS_ENABLE: Enable Advanced Failsafe¶
This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
AFS_MAN_PIN: Manual Pin¶
This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
AFS_HB_PIN: Heartbeat Pin¶
This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
Values |
||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AFS_WP_COMMS: Comms Waypoint¶
Waypoint number to navigate to on comms loss
AFS_WP_GPS_LOSS: GPS Loss Waypoint¶
Waypoint number to navigate to on GPS lock loss
AFS_TERMINATE: Force Terminate¶
Can be set in flight to force termination of the heartbeat signal
AFS_TERM_ACTION: Terminate action¶
This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter
AFS_TERM_PIN: Terminate Pin¶
This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
Values |
||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AFS_AMSL_LIMIT: AMSL limit¶
This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
Units |
---|
meters |
AFS_AMSL_ERR_GPS: Error margin for GPS based AMSL limit¶
This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
Units |
---|
meters |
AFS_QNH_PRESSURE: QNH pressure¶
This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
Units |
---|
hectopascal |
AFS_MAX_GPS_LOSS: Maximum number of GPS loss events¶
Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
AFS_MAX_COM_LOSS: Maximum number of comms loss events¶
Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
AFS_GEOFENCE: Enable geofence Advanced Failsafe¶
This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC: Enable RC Advanced Failsafe¶
This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC_MAN_ONLY: Enable RC Termination only in manual control modes¶
If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
AFS_DUAL_LOSS: Enable dual loss terminate due to failure of both GCS and GPS simultaneously¶
This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
AFS_RC_FAIL_TIME: RC failure time¶
This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
Units |
---|
seconds |
AFS_MAX_RANGE: Max allowed range¶
This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
Units |
---|
kilometers |
AFS_OPTIONS: AFS options¶
See description for each bitmask bit description
Bitmask |
||||||
---|---|---|---|---|---|---|
|
AFS_GCS_TIMEOUT: GCS timeout¶
The time (in seconds) of persistent data link loss before GCS failsafe occurs.
Units |
---|
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_REQUIRE: Require Arming Motors¶
Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will occur using either rudder stick arming (if enabled) or GCS command when all mandatory and ARMING_CHECK items are satisfied. Note, when setting this parameter to 0, a reboot is required to immediately arm the plane.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
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 |
ATC Parameters¶
ATC_STR_RAT_P: Steering control rate P gain¶
Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
Increment |
Range |
---|---|
0.001 |
0.000 to 2.000 |
ATC_STR_RAT_I: Steering control I gain¶
Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
Increment |
Range |
---|---|
0.001 |
0.000 to 2.000 |
ATC_STR_RAT_IMAX: Steering control I gain maximum¶
Steering control I gain maximum. Constrains the steering output (range -1 to +1) that the I term will generate
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_STR_RAT_D: Steering control D gain¶
Steering control D gain. Compensates for short-term change in desired turn rate vs actual
Increment |
Range |
---|---|
0.001 |
0.000 to 0.400 |
ATC_STR_RAT_FF: Steering control feed forward¶
Steering control feed forward
Increment |
Range |
---|---|
0.001 |
0.000 to 3.000 |
ATC_STR_RAT_FILT: Steering control filter frequency¶
Steering control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_STR_RAT_FLTT: Steering control Target filter frequency in Hz¶
Target filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_STR_RAT_FLTE: Steering control Error filter frequency in Hz¶
Error filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_STR_RAT_FLTD: Steering control Derivative term filter frequency in Hz¶
Derivative filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_STR_RAT_SMAX: Steering slew rate limit¶
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
---|---|
0.5 |
0 to 200 |
ATC_STR_RAT_PDMX: Steering control PD sum maximum¶
Steering control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_STR_RAT_D_FF: Steering control 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.03 |
ATC_STR_RAT_NTF: Steering control Target notch filter index¶
Steering control Target notch filter index
Range |
---|
1 to 8 |
ATC_STR_RAT_NEF: Steering control Error notch filter index¶
Steering control Error notch filter index
Range |
---|
1 to 8 |
ATC_SPEED_P: Speed control P gain¶
Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
Increment |
Range |
---|---|
0.01 |
0.010 to 2.000 |
ATC_SPEED_I: Speed control I gain¶
Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
Increment |
Range |
---|---|
0.01 |
0.000 to 2.000 |
ATC_SPEED_IMAX: Speed control I gain maximum¶
Speed control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_SPEED_D: Speed control D gain¶
Speed control D gain. Compensates for short-term change in desired speed vs actual
Increment |
Range |
---|---|
0.001 |
0.000 to 0.400 |
ATC_SPEED_FF: Speed control feed forward¶
Speed control feed forward
Increment |
Range |
---|---|
0.001 |
0.000 to 0.500 |
ATC_SPEED_FILT: Speed control filter frequency¶
Speed control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SPEED_FLTT: Speed control Target filter frequency in Hz¶
Target filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SPEED_FLTE: Speed control Error filter frequency in Hz¶
Error filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SPEED_FLTD: Speed control Derivative term filter frequency in Hz¶
Derivative filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SPEED_SMAX: Speed control slew rate limit¶
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
---|---|
0.5 |
0 to 200 |
ATC_SPEED_PDMX: Speed control PD sum maximum¶
Speed control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_SPEED_D_FF: Speed control 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.03 |
ATC_SPEED_NTF: Speed control Target notch filter index¶
Speed control Target notch filter index
Range |
---|
1 to 8 |
ATC_SPEED_NEF: Speed control Error notch filter index¶
Speed control Error notch filter index
Range |
---|
1 to 8 |
ATC_ACCEL_MAX: Speed control acceleration (and deceleration) maximum in m/s/s¶
Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
Increment |
Range |
Units |
---|---|---|
0.1 |
0.0 to 10.0 |
meters per square second |
ATC_BRAKE: Speed control brake enable/disable¶
Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
Values |
||||||
---|---|---|---|---|---|---|
|
ATC_STOP_SPEED: Speed control stop speed¶
Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
Increment |
Range |
Units |
---|---|---|
0.01 |
0.00 to 0.50 |
meters per second |
ATC_STR_ANG_P: Steering control angle P gain¶
Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
Increment |
Range |
---|---|
0.1 |
1.000 to 10.000 |
ATC_STR_ACC_MAX: Steering control angular acceleration maximum¶
Steering control angular acceleration maximum (in deg/s/s). 0 to disable acceleration limiting
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 1000 |
degrees per square second |
ATC_STR_RAT_MAX: Steering control rotation rate maximum¶
Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
Increment |
Range |
Units |
---|---|---|
0.1 |
0 to 1000 |
degrees per second |
ATC_DECEL_MAX: Speed control deceleration maximum in m/s/s¶
Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
Increment |
Range |
Units |
---|---|---|
0.1 |
0.0 to 10.0 |
meters per square second |
ATC_BAL_P: Pitch control P gain¶
Pitch control P gain for BalanceBots. Converts the error between the desired pitch (in radians) and actual pitch to a motor output (in the range -1 to +1)
Increment |
Range |
---|---|
0.01 |
0.000 to 2.000 |
ATC_BAL_I: Pitch control I gain¶
Pitch control I gain for BalanceBots. Corrects long term error between the desired pitch (in radians) and actual pitch
Increment |
Range |
---|---|
0.01 |
0.000 to 2.000 |
ATC_BAL_IMAX: Pitch control I gain maximum¶
Pitch control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_BAL_D: Pitch control D gain¶
Pitch control D gain. Compensates for short-term change in desired pitch vs actual
Increment |
Range |
---|---|
0.001 |
0.000 to 0.100 |
ATC_BAL_FF: Pitch control feed forward¶
Pitch control feed forward
Increment |
Range |
---|---|
0.001 |
0.000 to 0.500 |
ATC_BAL_FILT: Pitch control filter frequency¶
Pitch control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_BAL_FLTT: Pitch control Target filter frequency in Hz¶
Pitch control Target filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_BAL_FLTE: Pitch control Error filter frequency in Hz¶
Pitch control Error filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_BAL_FLTD: Pitch control Derivative term filter frequency in Hz¶
Pitch control Derivative filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_BAL_SMAX: Pitch control slew rate limit¶
Pitch control upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
---|---|
0.5 |
0 to 200 |
ATC_BAL_PDMX: Pitch control PD sum maximum¶
Pitch control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_BAL_D_FF: Pitch control 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.03 |
ATC_BAL_NTF: Pitch control Target notch filter index¶
Pitch control Target notch filter index
Range |
---|
1 to 8 |
ATC_BAL_NEF: Pitch control Error notch filter index¶
Pitch control Error notch filter index
Range |
---|
1 to 8 |
ATC_BAL_PIT_FF: Pitch control feed forward from current pitch angle¶
Pitch control feed forward from current pitch angle
Increment |
Range |
---|---|
0.01 |
0.0 to 1.0 |
ATC_SAIL_P: Sail Heel control P gain¶
Sail Heel control P gain for sailboats. Converts the error between the desired heel angle (in radians) and actual heel to a main sail output (in the range -1 to +1)
Increment |
Range |
---|---|
0.01 |
0.000 to 2.000 |
ATC_SAIL_I: Sail Heel control I gain¶
Sail Heel control I gain for sailboats. Corrects long term error between the desired heel angle (in radians) and actual
Increment |
Range |
---|---|
0.01 |
0.000 to 2.000 |
ATC_SAIL_IMAX: Sail Heel control I gain maximum¶
Sail Heel control I gain maximum. Constrains the maximum I term contribution to the main sail output (range -1 to +1)
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_SAIL_D: Sail Heel control D gain¶
Sail Heel control D gain. Compensates for short-term change in desired heel angle vs actual
Increment |
Range |
---|---|
0.001 |
0.000 to 0.100 |
ATC_SAIL_FF: Sail Heel control feed forward¶
Sail Heel control feed forward
Increment |
Range |
---|---|
0.001 |
0.000 to 0.500 |
ATC_SAIL_FILT: Sail Heel control filter frequency¶
Sail Heel control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SAIL_FLTT: Sail Heel Target filter frequency in Hz¶
Target filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SAIL_FLTE: Sail Heel Error filter frequency in Hz¶
Error filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SAIL_FLTD: Sail Heel Derivative term filter frequency in Hz¶
Derivative filter frequency in Hz
Increment |
Range |
Units |
---|---|---|
0.1 |
0.000 to 100.000 |
hertz |
ATC_SAIL_SMAX: Sail heel slew rate limit¶
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
---|---|
0.5 |
0 to 200 |
ATC_SAIL_PDMX: Sail Heel control PD sum maximum¶
Sail Heel control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
Increment |
Range |
---|---|
0.01 |
0.000 to 1.000 |
ATC_SAIL_D_FF: Sail Heel 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.03 |
ATC_SAIL_NTF: Sail Heel Target notch filter index¶
Sail Heel Target notch filter index
Range |
---|
1 to 8 |
ATC_SAIL_NEF: Sail Heel Error notch filter index¶
Sail Heel Error notch filter index
Range |
---|
1 to 8 |
ATC_TURN_MAX_G: Turning maximum G force¶
The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
Increment |
Range |
Units |
---|---|---|
0.01 |
0.1 to 10 |
standard acceleration due to gravity |
ATC_BAL_LIM_TC: Pitch control limit time constant¶
Pitch control limit time constant to protect against falling. Lower values limit pitch more quickly, higher values limit more slowly. Set to 0 to disable
Increment |
Range |
---|---|
0.01 |
0.0 to 5.0 |
ATC_BAL_LIM_THR: Pitch control limit throttle threshold¶
Pitch control limit throttle threshold. Pitch angle will be limited if throttle crosses this threshold (from 0 to 1)
Increment |
Range |
---|---|
0.01 |
0.0 to 1.0 |
AVOID_ Parameters¶
AVOID_ENABLE: Avoidance control enable/disable¶
Enabled/disable avoidance input sources
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
AVOID_MARGIN: Avoidance distance margin in GPS modes¶
Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes
Range |
Units |
---|---|
1 to 10 |
meters |
AVOID_BEHAVE: Avoidance behaviour¶
Avoidance behaviour (slide or stop)
Values |
||||||
---|---|---|---|---|---|---|
|
AVOID_BACKUP_SPD: Avoidance maximum horizontal backup speed¶
Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup.
Range |
Units |
---|---|
0 to 2 |
meters per second |
AVOID_ACCEL_MAX: Avoidance maximum acceleration¶
Maximum acceleration with which obstacles will be avoided with. Set zero to disable acceleration limits
Range |
Units |
---|---|
0 to 9 |
meters per square second |
AVOID_BACKUP_DZ: Avoidance deadzone between stopping and backing away from obstacle¶
Distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles. Increase this parameter if you see vehicle going back and forth in front of obstacle.
Range |
Units |
---|---|
0 to 2 |
meters |
AVOID_BACKZ_SPD: Avoidance maximum vertical backup speed¶
Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup.
Range |
Units |
---|---|
0 to 2 |
meters per second |
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 |
|||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|