Complete Parameter List¶
Full Parameter List of Copter stable V4.4.4
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.
ArduCopter Parameters¶
FORMAT_VERSION: Eeprom format version number¶
This value is incremented when changes are made to the eeprom format
ReadOnly |
---|
True |
SYSID_THISMAV: MAVLink system ID of this vehicle¶
Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
Range |
---|
1 to 255 |
SYSID_MYGCS: My ground station number¶
Allows restricting radio overrides to only come from my ground station
Range |
---|
1 to 255 |
PILOT_THR_FILT: Throttle filter cutoff¶
Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
Increment |
Range |
Units |
---|---|---|
.5 |
0 to 10 |
hertz |
PILOT_TKOFF_ALT: Pilot takeoff altitude¶
Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
Increment |
Range |
Units |
---|---|---|
10 |
0.0 to 1000.0 |
centimeters |
PILOT_THR_BHV: Throttle stick behavior¶
Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.
Bitmask |
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
|
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 |
Values |
||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
|
RTL_ALT: RTL Altitude¶
The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.
Increment |
Range |
Units |
---|---|---|
1 |
200 to 300000 |
centimeters |
RTL_CONE_SLOPE: RTL cone slope¶
Defines a cone above home which determines maximum climb
Increment |
Range |
Values |
||||||||
---|---|---|---|---|---|---|---|---|---|---|
.1 |
0.5 to 10.0 |
|
RTL_SPEED: RTL speed¶
Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
Increment |
Range |
Units |
---|---|---|
50 |
0 to 2000 |
centimeters per second |
RTL_ALT_FINAL: RTL Final Altitude¶
This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 1000 |
centimeters |
RTL_CLIMB_MIN: RTL minimum climb¶
The vehicle will climb this many cm during the initial climb portion of the RTL
Increment |
Range |
Units |
---|---|---|
10 |
0 to 3000 |
centimeters |
RTL_LOIT_TIME: RTL loiter time¶
Time (in milliseconds) to loiter above home before beginning final descent
Increment |
Range |
Units |
---|---|---|
1000 |
0 to 60000 |
milliseconds |
RTL_ALT_TYPE: RTL mode altitude type¶
RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
Values |
||||||
---|---|---|---|---|---|---|
|
FS_GCS_ENABLE: Ground Station Failsafe Enable¶
Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
GPS_HDOP_GOOD: GPS Hdop Good¶
GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
Range |
---|
100 to 900 |
SUPER_SIMPLE: Super Simple Mode¶
Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
WP_YAW_BEHAVIOR: Yaw behaviour during missions¶
Determines how the autopilot controls the yaw during missions and RTL
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
LAND_SPEED: Land speed¶
The descent speed for the final stage of landing in cm/s
Increment |
Range |
Units |
---|---|---|
10 |
30 to 200 |
centimeters per second |
LAND_SPEED_HIGH: Land speed high¶
The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
Increment |
Range |
Units |
---|---|---|
10 |
0 to 500 |
centimeters per second |
PILOT_SPEED_UP: Pilot maximum vertical speed ascending¶
The maximum vertical ascending velocity the pilot may request in cm/s
Increment |
Range |
Units |
---|---|---|
10 |
50 to 500 |
centimeters per second |
PILOT_ACCEL_Z: Pilot vertical acceleration¶
The vertical acceleration used when pilot is controlling the altitude
Increment |
Range |
Units |
---|---|---|
10 |
50 to 500 |
centimeters per square second |
FS_THR_ENABLE: Throttle Failsafe Enable¶
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FS_THR_VALUE: Throttle Failsafe Value¶
The PWM level in microseconds on channel 3 below which throttle failsafe triggers
Increment |
Range |
Units |
---|---|---|
1 |
910 to 1100 |
PWM in microseconds |
THR_DZ: Throttle deadzone¶
The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
Increment |
Range |
Units |
---|---|---|
1 |
0 to 300 |
PWM in microseconds |
FLTMODE1: Flight Mode 1¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE2: Flight Mode 2¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE3: Flight Mode 3¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE4: Flight Mode 4¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE5: Flight Mode 5¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE6: Flight Mode 6¶
Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FLTMODE_CH: Flightmode channel¶
RC Channel to use for flight mode control
Values |
||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
INITIAL_MODE: Initial flight mode¶
This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
SIMPLE: Simple mode bitmask¶
Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
LOG_BITMASK: Log bitmask¶
Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535.
Bitmask |
||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ESC_CALIBRATION: ESC Calibration¶
Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
TUNE: Channel 6 Tuning¶
Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FRAME_TYPE: Frame Type (+, X, V, etc)¶
Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
Values |
||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
DISARM_DELAY: Disarm delay¶
Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.
Range |
Units |
---|---|
0 to 127 |
seconds |
ANGLE_MAX: Angle Max¶
Maximum lean angle in all flight modes
Increment |
Range |
Units |
---|---|---|
10 |
1000 to 8000 |
centidegrees |
PHLD_BRAKE_RATE: PosHold braking rate¶
PosHold flight mode's rotation rate during braking in deg/sec
Range |
Units |
---|---|
4 to 12 |
degrees per second |
PHLD_BRAKE_ANGLE: PosHold braking angle max¶
PosHold flight mode's max lean angle during braking in centi-degrees
Increment |
Range |
Units |
---|---|---|
10 |
2000 to 4500 |
centidegrees |
LAND_REPOSITION: Land repositioning¶
Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
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, velocity, position and height variances. Used in arming check and EKF failsafe.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
FS_CRASH_CHECK: Crash check enable¶
This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
Values |
||||||
---|---|---|---|---|---|---|
|
RC_SPEED: ESC Update Speed¶
This is the speed in Hertz that your ESCs will receive updates
Increment |
Range |
Units |
---|---|---|
1 |
50 to 490 |
hertz |
ACRO_BAL_ROLL: Acro Balance Roll¶
rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.
Increment |
Range |
---|---|
0.1 |
0 to 3 |
ACRO_BAL_PITCH: Acro Balance Pitch¶
rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.
Increment |
Range |
---|---|
0.1 |
0 to 3 |
ACRO_TRAINER: Acro Trainer¶
Type of trainer used in acro mode
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
THROW_MOT_START: Start motors before throwing is detected¶
Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
Values |
||||||
---|---|---|---|---|---|---|
|
THROW_NEXTMODE: Throw mode's follow up mode¶
Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
THROW_TYPE: Type of Type¶
Used by Throw mode. Specifies whether Copter is thrown upward or dropped.
Values |
||||||
---|---|---|---|---|---|---|
|
GND_EFFECT_COMP: Ground Effect Compensation Enable/Disable¶
Ground Effect Compensation Enable/Disable
Values |
||||||
---|---|---|---|---|---|---|
|
DEV_OPTIONS: Development options¶
Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
Bitmask |
||||||
---|---|---|---|---|---|---|
|
ACRO_THR_MID: Acro Thr Mid¶
Acro Throttle Mid
Range |
---|
0 to 1 |
SYSID_ENFORCE: GCS sysid enforcement¶
This controls whether packets from other than the expected GCS system ID will be accepted
Values |
||||||
---|---|---|---|---|---|---|
|
FRAME_CLASS: Frame Class¶
Controls major frame class for multicopter component
Values |
||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
PILOT_SPEED_DN: Pilot maximum vertical speed descending¶
The maximum vertical descending velocity the pilot may request in cm/s. If 0 PILOT_SPEED_UP value is used.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 500 |
centimeters per second |
LAND_ALT_LOW: Land alt low¶
Altitude during Landing at which vehicle slows to LAND_SPEED
Increment |
Range |
Units |
---|---|---|
10 |
100 to 10000 |
centimeters |
TUNE_MIN: Tuning minimum¶
Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to
TUNE_MAX: Tuning maximum¶
Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to
FS_VIBE_ENABLE: Vibration Failsafe enable¶
This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations
Values |
||||||
---|---|---|---|---|---|---|
|
FS_OPTIONS: Failsafe options bitmask¶
Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.
Bitmask |
Values |
||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
|
ACRO_OPTIONS: Acro mode options¶
A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.
Bitmask |
||||||
---|---|---|---|---|---|---|
|
AUTO_OPTIONS: Auto mode options¶
A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
GUID_OPTIONS: Guided mode options¶
Options that can be applied to change guided mode behaviour
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FS_GCS_TIMEOUT: GCS failsafe timeout¶
Timeout before triggering the GCS failsafe
Increment |
Range |
Units |
---|---|---|
1 |
2 to 120 |
seconds |
RTL_OPTIONS: RTL mode options¶
Options that can be applied to change RTL mode behaviour
Bitmask |
||||
---|---|---|---|---|
|
FLIGHT_OPTIONS: Flight mode options¶
Flight mode specific options
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
RNGFND_FILT: Rangefinder filter¶
Rangefinder filter to smooth distance. Set to zero to disable filtering
Increment |
Range |
Units |
---|---|---|
0.05 |
0 to 5 |
hertz |
GUID_TIMEOUT: Guided mode timeout¶
Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control
Range |
Units |
---|---|
0.1 to 5 |
seconds |
SURFTRAK_MODE: Surface Tracking Mode¶
set which surface to track in surface tracking
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
FS_DR_ENABLE: DeadReckon Failsafe Action¶
Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
FS_DR_TIMEOUT: DeadReckon Failsafe Timeout¶
DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate
Range |
---|
0 to 120 |
ACRO_RP_RATE: Acro Roll and Pitch Rate¶
Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation
Range |
Units |
---|---|
1 to 1080 |
degrees per second |
ACRO_RP_EXPO: Acro Roll/Pitch Expo¶
Acro roll/pitch Expo to allow faster rotation when stick at edges
Range |
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
-0.5 to 0.95 |
|
ACRO_RP_RATE_TC: Acro roll/pitch rate control input time constant¶
Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0.01 |
0 to 1 |
seconds |
|
ACRO_Y_RATE: Acro Yaw Rate¶
Acro mode maximum yaw rate. Higher value means faster rate of rotation
Range |
Units |
---|---|
1 to 360 |
degrees per second |
ACRO_Y_EXPO: Acro Yaw Expo¶
Acro yaw expo to allow faster rotation when stick at edges
Range |
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
-1.0 to 0.95 |
|
ACRO_Y_RATE_TC: Acro yaw rate control input time constant¶
Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0.01 |
0 to 1 |
seconds |
|
PILOT_Y_RATE: Pilot controlled yaw rate¶
Pilot controlled yaw rate max. Used in all pilot controlled modes except Acro
Range |
Units |
---|---|
1 to 360 |
degrees per second |
PILOT_Y_EXPO: Pilot controlled yaw expo¶
Pilot controlled yaw expo to allow faster rotation when stick at edges
Range |
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
-0.5 to 1.0 |
|
PILOT_Y_RATE_TC: Pilot yaw rate control input time constant¶
Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0.01 |
0 to 1 |
seconds |
|
TKOFF_SLEW_TIME: Slew time of throttle during take-off¶
Time to slew the throttle from minimum to maximum while checking for a succsessful takeoff.
Range |
Units |
---|---|
0.25 to 5.0 |
seconds |
TKOFF_RPM_MIN: Takeoff Check RPM minimum¶
Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check
Range |
---|
0 to 10000 |
PLDP_THRESH: Payload Place thrust ratio threshold¶
Ratio of vertical thrust during decent below which payload touchdown will trigger.
Range |
---|
0.5 to 0.9 |
PLDP_RNG_MIN: Payload Place minimum range finder altitude¶
Minimum range finder altitude in m to trigger payload touchdown, set to zero to disable.
Range |
Units |
---|---|
0 to 100 |
meters |
PLDP_DELAY: Payload Place climb delay¶
Delay after release, in seconds, before aircraft starts to climb back to starting altitude.
Range |
Units |
---|---|
0 to 120 |
seconds |
PLDP_SPEED_DN: Payload Place decent speed¶
The maximum vertical decent velocity in m/s. If 0 LAND_SPEED value is used.
Range |
Units |
---|---|
0 to 5 |
meters per second |
SURFTRAK_TC: Surface Tracking Filter Time Constant¶
Time to achieve 63.2% of the surface altitude measurement change. If 0 filtering is disabled
Range |
Units |
---|---|
0 to 5 |
seconds |
ADSB_ Parameters¶
ADSB_TYPE: ADSB Type¶
Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ADSB_LIST_MAX: ADSB vehicle list size¶
ADSB list size of nearest vehicles. Longer lists take longer to refresh with lower SRx_ADSB values.
Range |
---|
1 to 100 |
ADSB_LIST_RADIUS: ADSB vehicle list radius filter¶
ADSB vehicle list radius filter. Vehicles detected outside this radius will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.
Range |
Units |
---|---|
0 to 100000 |
meters |
ADSB_ICAO_ID: ICAO_ID vehicle identification number¶
ICAO_ID unique vehicle identification number of this aircraft. This is an integer limited to 24bits. If set to 0 then one will be randomly generated. If set to -1 then static information is not sent, transceiver is assumed pre-programmed.
Range |
---|
-1 to 16777215 |
ADSB_EMIT_TYPE: Emitter type¶
ADSB classification for the type of vehicle emitting the transponder signal. Default value is 14 (UAV).
Values |
||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ADSB_LEN_WIDTH: Aircraft length and width¶
Aircraft length and width dimension options in Length and Width in meters. In most cases, use a value of 1 for smallest size.
Values |
||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ADSB_OFFSET_LAT: GPS antenna lateral offset¶
GPS antenna lateral offset. This describes the physical location offest from center of the GPS antenna on the aircraft.
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ADSB_OFFSET_LON: GPS antenna longitudinal offset¶
GPS antenna longitudinal offset. This is usually set to 1, Applied By Sensor
Values |
||||||
---|---|---|---|---|---|---|
|
ADSB_RF_SELECT: Transceiver RF selection¶
Transceiver RF selection for Rx enable and/or Tx enable. This only effects devices that can Tx and/or Rx. Rx-only devices should override this to always be Rx-only.
Bitmask |
||||||
---|---|---|---|---|---|---|
|
ADSB_SQUAWK: Squawk code¶
VFR squawk (Mode 3/A) code is a pre-programmed default code when the pilot is flying VFR and not in contact with ATC. In the USA, the VFR squawk code is octal 1200 (hex 0x280, decimal 640) and in most parts of Europe the VFR squawk code is octal 7000. If an invalid octal number is set then it will be reset to 1200.
Range |
Units |
---|---|
0 to 7777 |
octal |
ADSB_RF_CAPABLE: RF capabilities¶
Describes your hardware RF In/Out capabilities.
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
ADSB_LIST_ALT: ADSB vehicle list altitude filter¶
ADSB vehicle list altitude filter. Vehicles detected above this altitude will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.
Range |
Units |
---|---|
0 to 32767 |
meters |
ADSB_ICAO_SPECL: ICAO_ID of special vehicle¶
ICAO_ID of special vehicle that ignores ADSB_LIST_RADIUS and ADSB_LIST_ALT. The vehicle is always tracked. Use 0 to disable.
ADSB_LOG: ADS-B logging¶
0: no logging, 1: log only special ID, 2:log all
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
ADSB_OPTIONS: ADS-B Options¶
Options for emergency failsafe codes and device capabilities
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 |
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. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is. See ARSPD_OPTIONS and ARSPD_MAX_WIND to disable airspeed sensors.
Increment |
Range |
Units |
---|---|---|
1 |
0 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 |
AIS_ Parameters¶
AIS_TYPE: AIS receiver type¶
AIS receiver type
Values |
||||||
---|---|---|---|---|---|---|
|
AIS_LIST_MAX: AIS vessel list size¶
AIS list size of nearest vessels. Longer lists take longer to refresh with lower SRx_ADSB values.
Range |
---|
1 to 100 |
AIS_TIME_OUT: AIS vessel time out¶
if no updates are received in this time a vessel will be removed from the list
Range |
Units |
---|---|
1 to 2000 |
seconds |
AIS_LOGGING: AIS logging options¶
Bitmask of AIS logging options
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARMING_ Parameters¶
ARMING_ACCTHRESH: Accelerometer error threshold¶
Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
Range |
Units |
---|---|
0.25 to 3.0 |
meters per square second |
ARMING_RUDDER: Arming with Rudder enable/disable¶
Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode!
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
ARMING_MIS_ITEMS: Required mission items¶
Bitmask of mission items that are required to be planned in order to arm the aircraft
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARMING_CHECK: Arm Checks to Perform (bitmask)¶
Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. For most users it is recommended to leave this at the default of 1 (all checks enabled). You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72.
Bitmask |
||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
ARMING_OPTIONS: Arming options¶
Options that can be applied to change arming behaviour
Values |
||||||
---|---|---|---|---|---|---|
|
AROT_ Parameters¶
AROT_ENABLE: Enable settings for RSC Setpoint¶
Allows you to enable (1) or disable (0) the autonomous autorotation capability.
Values |
||||||
---|---|---|---|---|---|---|
|
AROT_HS_P: P gain for head speed controller¶
Increase value to increase sensitivity of head speed controller during autonomous autorotation.
Increment |
Range |
---|---|
0.01 |
0.3 to 1 |
AROT_HS_SET_PT: Target Head Speed¶
The target head speed in RPM during autorotation. Start by setting to desired hover speed and tune from there as necessary.
Increment |
Range |
Units |
---|---|---|
1 |
1000 to 2800 |
Revolutions Per Minute |
AROT_TARG_SP: Target Glide Ground Speed¶
Target ground speed in cm/s for the autorotation controller to try and achieve/ maintain during the glide phase.
Increment |
Range |
Units |
---|---|---|
50 |
800 to 2000 |
centimeters per second |
AROT_COL_FILT_E: Entry Phase Collective Filter¶
Cut-off frequency for collective low pass filter. For the entry phase. Acts as a following trim. Must be higher than AROT_COL_FILT_G.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.2 to 0.5 |
hertz |
AROT_COL_FILT_G: Glide Phase Collective Filter¶
Cut-off frequency for collective low pass filter. For the glide phase. Acts as a following trim. Must be lower than AROT_COL_FILT_E.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.03 to 0.15 |
hertz |
AROT_AS_ACC_MAX: Forward Acceleration Limit¶
Maximum forward acceleration to apply in speed controller.
Increment |
Range |
Units |
---|---|---|
10 |
30 to 60 |
centimeters per square second |
AROT_BAIL_TIME: Bail Out Timer¶
Time in seconds from bail out initiated to the exit of autorotation flight mode.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 4 |
seconds |
AROT_HS_SENSOR: Main Rotor RPM Sensor¶
Allocate the RPM sensor instance to use for measuring head speed. RPM1 = 0. RPM2 = 1.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 3 |
seconds |
AROT_FW_V_P: Velocity (horizontal) P gain¶
Velocity (horizontal) P gain. Determines the propotion of the target acceleration based on the velocity error.
Increment |
Range |
---|---|
0.1 |
0.1 to 6.0 |
AROT_FW_V_FF: Velocity (horizontal) feed forward¶
Velocity (horizontal) input filter. Corrects the target acceleration proportionally to the desired velocity.
Increment |
Range |
---|---|
0.01 |
0 to 1 |
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 ground 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 calibraions 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. Set to 15 on the Pixhawk for the analog airspeed port.
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. Set to 15 on the Pixhawk for the analog airspeed port.
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_SLEW_YAW: Yaw target slew rate¶
Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
Increment |
Range |
Units |
---|---|---|
100 |
500 to 18000 |
centidegrees per second |
ATC_ACCEL_Y_MAX: Acceleration Max for Yaw¶
Maximum acceleration in yaw axis
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1000 |
0 to 72000 |
centidegrees per square second |
|
ATC_RATE_FF_ENAB: Rate Feedforward Enable¶
Controls whether body-frame rate feedfoward is enabled or disabled
Values |
||||||
---|---|---|---|---|---|---|
|
ATC_ACCEL_R_MAX: Acceleration Max for Roll¶
Maximum acceleration in roll axis
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1000 |
0 to 180000 |
centidegrees per square second |
|
ATC_ACCEL_P_MAX: Acceleration Max for Pitch¶
Maximum acceleration in pitch axis
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1000 |
0 to 180000 |
centidegrees per square second |
|
ATC_ANGLE_BOOST: Angle Boost¶
Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
Values |
||||||
---|---|---|---|---|---|---|
|
ATC_ANG_RLL_P: Roll axis angle controller P gain¶
Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
Range |
---|
3.000 to 12.000 |
ATC_ANG_PIT_P: Pitch axis angle controller P gain¶
Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
Range |
---|
3.000 to 12.000 |
ATC_ANG_YAW_P: Yaw axis angle controller P gain¶
Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
Range |
---|
3.000 to 12.000 |
ATC_ANG_LIM_TC: Angle Limit (to maintain altitude) Time Constant¶
Angle Limit (to maintain altitude) Time Constant
Range |
---|
0.5 to 10.0 |
ATC_RATE_R_MAX: Angular Velocity Max for Roll¶
Maximum angular velocity in roll axis
Increment |
Range |
Units |
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1 |
0 to 1080 |
degrees per second |
|
ATC_RATE_P_MAX: Angular Velocity Max for Pitch¶
Maximum angular velocity in pitch axis
Increment |
Range |
Units |
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1 |
0 to 1080 |
degrees per second |
|
ATC_RATE_Y_MAX: Angular Velocity Max for Yaw¶
Maximum angular velocity in yaw axis
Increment |
Range |
Units |
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|
1 |
0 to 1080 |
degrees per second |
|
ATC_INPUT_TC: Attitude control input time constant¶
Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
Increment |
Range |
Units |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0.01 |
0 to 1 |
seconds |
|
ATC_RAT_RLL_P (AC_AttitudeControl_Multi): Roll axis rate controller P gain¶
Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.005 |
0.01 to 0.5 |
ATC_RAT_RLL_I (AC_AttitudeControl_Multi): Roll axis rate controller I gain¶
Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.01 |
0.01 to 2.0 |
ATC_RAT_RLL_IMAX (AC_AttitudeControl_Multi): Roll axis rate controller I gain maximum¶
Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_RLL_D (AC_AttitudeControl_Multi): Roll axis rate controller D gain¶
Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.001 |
0.0 to 0.05 |
ATC_RAT_RLL_FF (AC_AttitudeControl_Multi): Roll axis rate controller feed forward¶
Roll axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0 to 0.5 |
ATC_RAT_RLL_FLTT (AC_AttitudeControl_Multi): Roll axis rate controller target frequency in Hz¶
Roll axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 100 |
hertz |
ATC_RAT_RLL_FLTE (AC_AttitudeControl_Multi): Roll axis rate controller error frequency in Hz¶
Roll axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 100 |
hertz |
ATC_RAT_RLL_FLTD (AC_AttitudeControl_Multi): Roll axis rate controller derivative frequency in Hz¶
Roll axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 100 |
hertz |
ATC_RAT_RLL_SMAX (AC_AttitudeControl_Multi): Roll 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_RAT_PIT_P (AC_AttitudeControl_Multi): Pitch axis rate controller P gain¶
Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate output
Increment |
Range |
---|---|
0.005 |
0.01 to 0.50 |
ATC_RAT_PIT_I (AC_AttitudeControl_Multi): Pitch axis rate controller I gain¶
Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
Increment |
Range |
---|---|
0.01 |
0.01 to 2.0 |
ATC_RAT_PIT_IMAX (AC_AttitudeControl_Multi): Pitch axis rate controller I gain maximum¶
Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_PIT_D (AC_AttitudeControl_Multi): Pitch axis rate controller D gain¶
Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
Increment |
Range |
---|---|
0.001 |
0.0 to 0.05 |
ATC_RAT_PIT_FF (AC_AttitudeControl_Multi): Pitch axis rate controller feed forward¶
Pitch axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0 to 0.5 |
ATC_RAT_PIT_FLTT (AC_AttitudeControl_Multi): Pitch axis rate controller target frequency in Hz¶
Pitch axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 100 |
hertz |
ATC_RAT_PIT_FLTE (AC_AttitudeControl_Multi): Pitch axis rate controller error frequency in Hz¶
Pitch axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 100 |
hertz |
ATC_RAT_PIT_FLTD (AC_AttitudeControl_Multi): Pitch axis rate controller derivative frequency in Hz¶
Pitch axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 100 |
hertz |
ATC_RAT_PIT_SMAX (AC_AttitudeControl_Multi): Pitch 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_RAT_YAW_P (AC_AttitudeControl_Multi): Yaw axis rate controller P gain¶
Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.005 |
0.10 to 2.50 |
ATC_RAT_YAW_I (AC_AttitudeControl_Multi): Yaw axis rate controller I gain¶
Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.01 |
0.010 to 1.0 |
ATC_RAT_YAW_IMAX (AC_AttitudeControl_Multi): Yaw axis rate controller I gain maximum¶
Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_YAW_D (AC_AttitudeControl_Multi): Yaw axis rate controller D gain¶
Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.001 |
0.000 to 0.02 |
ATC_RAT_YAW_FF (AC_AttitudeControl_Multi): Yaw axis rate controller feed forward¶
Yaw axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0 to 0.5 |
ATC_RAT_YAW_FLTT (AC_AttitudeControl_Multi): Yaw axis rate controller target frequency in Hz¶
Yaw axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
1 to 50 |
hertz |
ATC_RAT_YAW_FLTE (AC_AttitudeControl_Multi): Yaw axis rate controller error frequency in Hz¶
Yaw axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 20 |
hertz |
ATC_RAT_YAW_FLTD (AC_AttitudeControl_Multi): Yaw axis rate controller derivative frequency in Hz¶
Yaw axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_YAW_SMAX (AC_AttitudeControl_Multi): Yaw 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_THR_MIX_MIN: Throttle Mix Minimum¶
Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
Range |
---|
0.1 to 0.25 |
ATC_THR_MIX_MAX: Throttle Mix Maximum¶
Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
Range |
---|
0.5 to 0.9 |
ATC_THR_MIX_MAN: Throttle Mix Manual¶
Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
Range |
---|
0.1 to 0.9 |
ATC_THR_G_BOOST: Throttle-gain boost¶
Throttle-gain boost ratio. A value of 0 means no boosting is applied, a value of 1 means full boosting is applied. Describes the ratio increase that is applied to angle P and PD on pitch and roll.
Range |
---|
0 to 1 |
ATC_HOVR_ROL_TRM: Hover Roll Trim¶
Trim the hover roll angle to counter tail rotor thrust in a hover
Increment |
Range |
Units |
---|---|---|
10 |
0 to 1000 |
centidegrees |
ATC_RAT_RLL_P (AC_AttitudeControl_Heli): Roll axis rate controller P gain¶
Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.005 |
0.0 to 0.35 |
ATC_RAT_RLL_I (AC_AttitudeControl_Heli): Roll axis rate controller I gain¶
Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.01 |
0.0 to 0.6 |
ATC_RAT_RLL_IMAX (AC_AttitudeControl_Heli): Roll axis rate controller I gain maximum¶
Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_RLL_ILMI: Roll axis rate controller I-term leak minimum¶
Point below which I-term will not leak down
Range |
---|
0 to 1 |
ATC_RAT_RLL_D (AC_AttitudeControl_Heli): Roll axis rate controller D gain¶
Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
Increment |
Range |
---|---|
0.001 |
0.0 to 0.03 |
ATC_RAT_RLL_FF (AC_AttitudeControl_Heli): Roll axis rate controller feed forward¶
Roll axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0.05 to 0.5 |
ATC_RAT_RLL_FLTT (AC_AttitudeControl_Heli): Roll axis rate controller target frequency in Hz¶
Roll axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_RLL_FLTE (AC_AttitudeControl_Heli): Roll axis rate controller error frequency in Hz¶
Roll axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_RLL_FLTD (AC_AttitudeControl_Heli): Roll axis rate controller derivative frequency in Hz¶
Roll axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 50 |
hertz |
ATC_RAT_RLL_SMAX (AC_AttitudeControl_Heli): Roll 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_RAT_PIT_P (AC_AttitudeControl_Heli): Pitch axis rate controller P gain¶
Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate
Increment |
Range |
---|---|
0.005 |
0.0 to 0.35 |
ATC_RAT_PIT_I (AC_AttitudeControl_Heli): Pitch axis rate controller I gain¶
Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
Increment |
Range |
---|---|
0.01 |
0.0 to 0.6 |
ATC_RAT_PIT_IMAX (AC_AttitudeControl_Heli): Pitch axis rate controller I gain maximum¶
Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_PIT_ILMI: Pitch axis rate controller I-term leak minimum¶
Point below which I-term will not leak down
Range |
---|
0 to 1 |
ATC_RAT_PIT_D (AC_AttitudeControl_Heli): Pitch axis rate controller D gain¶
Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
Increment |
Range |
---|---|
0.001 |
0.0 to 0.03 |
ATC_RAT_PIT_FF (AC_AttitudeControl_Heli): Pitch axis rate controller feed forward¶
Pitch axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0.05 to 0.5 |
ATC_RAT_PIT_FLTT (AC_AttitudeControl_Heli): Pitch axis rate controller target frequency in Hz¶
Pitch axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_PIT_FLTE (AC_AttitudeControl_Heli): Pitch axis rate controller error frequency in Hz¶
Pitch axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_PIT_FLTD (AC_AttitudeControl_Heli): Pitch axis rate controller derivative frequency in Hz¶
Pitch axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 50 |
hertz |
ATC_RAT_PIT_SMAX (AC_AttitudeControl_Heli): Pitch 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_RAT_YAW_P (AC_AttitudeControl_Heli): Yaw axis rate controller P gain¶
Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.005 |
0.180 to 0.60 |
ATC_RAT_YAW_I (AC_AttitudeControl_Heli): Yaw axis rate controller I gain¶
Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.01 |
0.01 to 0.2 |
ATC_RAT_YAW_IMAX (AC_AttitudeControl_Heli): Yaw axis rate controller I gain maximum¶
Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output
Increment |
Range |
---|---|
0.01 |
0 to 1 |
ATC_RAT_YAW_ILMI: Yaw axis rate controller I-term leak minimum¶
Point below which I-term will not leak down
Range |
---|
0 to 1 |
ATC_RAT_YAW_D (AC_AttitudeControl_Heli): Yaw axis rate controller D gain¶
Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
Increment |
Range |
---|---|
0.001 |
0.000 to 0.02 |
ATC_RAT_YAW_FF (AC_AttitudeControl_Heli): Yaw axis rate controller feed forward¶
Yaw axis rate controller feed forward
Increment |
Range |
---|---|
0.001 |
0 to 0.5 |
ATC_RAT_YAW_FLTT (AC_AttitudeControl_Heli): Yaw axis rate controller target frequency in Hz¶
Yaw axis rate controller target frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_YAW_FLTE (AC_AttitudeControl_Heli): Yaw axis rate controller error frequency in Hz¶
Yaw axis rate controller error frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
5 to 50 |
hertz |
ATC_RAT_YAW_FLTD (AC_AttitudeControl_Heli): Yaw axis rate controller derivative frequency in Hz¶
Yaw axis rate controller derivative frequency in Hz
Increment |
Range |
Units |
---|---|---|
1 |
0 to 50 |
hertz |
ATC_RAT_YAW_SMAX (AC_AttitudeControl_Heli): Yaw 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_PIRO_COMP: Piro Comp Enable¶
Pirouette compensation enabled
Values |
||||||
---|---|---|---|---|---|---|
|
AUTOTUNE_ Parameters¶
AUTOTUNE_AXES (AC_AutoTune_Multi): Autotune axis bitmask¶
1-byte bitmap of axes to autotune
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
AUTOTUNE_AGGR: Autotune aggressiveness¶
Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
Range |
---|
0.05 to 0.10 |
AUTOTUNE_MIN_D: AutoTune minimum D¶
Defines the minimum D gain
Range |
---|
0.001 to 0.006 |
AUTOTUNE_AXES (AC_AutoTune_Heli): Autotune axis bitmask¶
1-byte bitmap of axes to autotune
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
AUTOTUNE_SEQ: AutoTune Sequence Bitmask¶
2-byte bitmask to select what tuning should be performed. Max gain automatically performed if Rate D is selected. Values: 7:All,1:VFF Only,2:Rate D/Rate P Only(incl max gain),4:Angle P Only,8:Max Gain Only,16:Tune Check,3:VFF and Rate D/Rate P(incl max gain),5:VFF and Angle P,6:Rate D/Rate P(incl max gain) and angle P
Bitmask |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AUTOTUNE_FRQ_MIN: AutoTune minimum sweep frequency¶
Defines the start frequency for sweeps and dwells
Range |
---|
10 to 30 |
AUTOTUNE_FRQ_MAX: AutoTune maximum sweep frequency¶
Defines the end frequency for sweeps and dwells
Range |
---|
50 to 120 |
AUTOTUNE_GN_MAX: AutoTune maximum response gain¶
Defines the response gain (output/input) to tune
Range |
---|
1 to 2.5 |
AUTOTUNE_VELXY_P: AutoTune velocity xy P gain¶
Velocity xy P gain used to hold position during Max Gain, Rate P, and Rate D frequency sweeps
Range |
---|
0 to 1 |
AVD_ Parameters¶
AVD_ENABLE: Enable Avoidance using ADSB¶
Enable Avoidance using ADSB
Values |
||||||
---|---|---|---|---|---|---|
|
AVD_F_ACTION: Collision Avoidance Behavior¶
Specifies aircraft behaviour when a collision is imminent
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
AVD_W_ACTION: Collision Avoidance Behavior - Warn¶
Specifies aircraft behaviour when a collision may occur
Values |
||||||
---|---|---|---|---|---|---|
|
AVD_F_RCVRY: Recovery behaviour after a fail event¶
Determines what the aircraft will do after a fail event is resolved
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
AVD_OBS_MAX: Maximum number of obstacles to track¶
Maximum number of obstacles to track
AVD_W_TIME: Time Horizon Warn¶
Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than W_DIST_XY or W_DIST_Z then W_ACTION is undertaken (assuming F_ACTION is not undertaken)
Units |
---|
seconds |
AVD_F_TIME: Time Horizon Fail¶
Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than F_DIST_XY or F_DIST_Z then F_ACTION is undertaken
Units |
---|
seconds |
AVD_W_DIST_XY: Distance Warn XY¶
Closest allowed projected distance before W_ACTION is undertaken
Units |
---|
meters |
AVD_F_DIST_XY: Distance Fail XY¶
Closest allowed projected distance before F_ACTION is undertaken
Units |
---|
meters |
AVD_W_DIST_Z: Distance Warn Z¶
Closest allowed projected distance before BEHAVIOUR_W is undertaken
Units |
---|
meters |
AVD_F_DIST_Z: Distance Fail Z¶
Closest allowed projected distance before BEHAVIOUR_F is undertaken
Units |
---|
meters |
AVD_F_ALT_MIN: ADS-B avoidance minimum altitude¶
Minimum AMSL (above mean sea level) altitude for ADS-B avoidance. If the vehicle is below this altitude, no avoidance action will take place. Useful to prevent ADS-B avoidance from activating while below the tree line or around structures. Default of 0 is no minimum.
Units |
---|
meters |
AVOID_ Parameters¶
AVOID_ENABLE: Avoidance control enable/disable¶
Enabled/disable avoidance input sources
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
AVOID_ANGLE_MAX: Avoidance max lean angle in non-GPS flight modes¶
Max lean angle used to avoid obstacles while in non-GPS modes
Increment |
Range |
Units |
---|---|---|
10 |
0 to 4500 |
centidegrees |
AVOID_DIST_MAX: Avoidance distance maximum in non-GPS flight modes¶
Distance from object at which obstacle avoidance will begin in non-GPS modes
Range |
Units |
---|---|
1 to 30 |
meters |
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 backup speed¶
Maximum speed that will be used to back away from obstacles in GPS modes (m/s). Set zero to disable
Range |
Units |
---|---|
0 to 2 |
meters per second |
AVOID_ALT_MIN: Avoidance minimum altitude¶
Minimum altitude above which proximity based avoidance will start working. This requires a valid downward facing rangefinder reading to work. Set zero to disable
Range |
Units |
---|---|
0 to 6 |
meters |
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 |
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_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: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT2_I2C_ADDR: 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. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT2_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
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_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: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT3_I2C_ADDR: 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. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT3_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
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_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: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT4_I2C_ADDR: 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. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT4_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
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_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: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT5_I2C_ADDR: 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. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT5_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATT6_ Parameters¶
BATT6_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT6_SERIAL_NUM: Battery serial number¶
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
BATT6_LOW_TIMER: Low voltage timeout¶
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 120 |
seconds |
BATT6_FS_VOLTSRC: Failsafe voltage source¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
BATT6_LOW_VOLT: Low battery voltage¶
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT6_LOW_MAH: Low battery capacity¶
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT6_CRT_VOLT: Critical battery voltage¶
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_CRT_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT6_CRT_MAH: Battery critical capacity¶
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6__FS_CRT_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT6_FS_LOW_ACT: Low battery failsafe action¶
What action the vehicle should perform if it hits a low battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_ARM_VOLT: Required arming voltage¶
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Increment |
Units |
---|---|
0.1 |
volt |
BATT6_ARM_MAH: Required arming remaining capacity¶
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT6__ARM_VOLT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT6_OPTIONS: Battery monitor options¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_VOLT_PIN: Battery Voltage sensing pin¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_VOLT_MULT: Voltage Multiplier¶
Used to convert the voltage of the voltage sensing pin (BATT6_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT6_AMP_PERVLT: Amps per volt¶
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
Units |
---|
ampere per volt |
BATT6_AMP_OFFSET: AMP offset¶
Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.
Units |
---|
volt |
BATT6_VLT_OFFSET: Voltage offset¶
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
Units |
---|
volt |
BATT6_I2C_BUS: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT6_I2C_ADDR: Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATT6_SUM_MASK: Battery Sum mask¶
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_CURR_MULT: Scales reported power monitor current¶
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
Range |
---|
.1 to 10 |
BATT6_FL_VLT_MIN: Empty fuel level voltage¶
The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
Units |
---|---|
0.01 to 10 |
volt |
BATT6_FL_V_MULT: Fuel level voltage multiplier¶
Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
---|
0.01 to 10 |
BATT6_FL_FLTR: Fuel level filter frequency¶
Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.
Range |
Units |
---|---|
-1 to 1 |
hertz |
BATT6_FL_PIN: Fuel level analog pin number¶
Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT6_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATT7_ Parameters¶
BATT7_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT7_SERIAL_NUM: Battery serial number¶
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
BATT7_LOW_TIMER: Low voltage timeout¶
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 120 |
seconds |
BATT7_FS_VOLTSRC: Failsafe voltage source¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
BATT7_LOW_VOLT: Low battery voltage¶
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT7_LOW_MAH: Low battery capacity¶
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT7_CRT_VOLT: Critical battery voltage¶
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_CRT_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT7_CRT_MAH: Battery critical capacity¶
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7__FS_CRT_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT7_FS_LOW_ACT: Low battery failsafe action¶
What action the vehicle should perform if it hits a low battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_ARM_VOLT: Required arming voltage¶
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Increment |
Units |
---|---|
0.1 |
volt |
BATT7_ARM_MAH: Required arming remaining capacity¶
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT7__ARM_VOLT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT7_OPTIONS: Battery monitor options¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_VOLT_PIN: Battery Voltage sensing pin¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_VOLT_MULT: Voltage Multiplier¶
Used to convert the voltage of the voltage sensing pin (BATT7_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT7_AMP_PERVLT: Amps per volt¶
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
Units |
---|
ampere per volt |
BATT7_AMP_OFFSET: AMP offset¶
Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.
Units |
---|
volt |
BATT7_VLT_OFFSET: Voltage offset¶
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
Units |
---|
volt |
BATT7_I2C_BUS: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT7_I2C_ADDR: Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATT7_SUM_MASK: Battery Sum mask¶
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_CURR_MULT: Scales reported power monitor current¶
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
Range |
---|
.1 to 10 |
BATT7_FL_VLT_MIN: Empty fuel level voltage¶
The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
Units |
---|---|
0.01 to 10 |
volt |
BATT7_FL_V_MULT: Fuel level voltage multiplier¶
Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
---|
0.01 to 10 |
BATT7_FL_FLTR: Fuel level filter frequency¶
Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.
Range |
Units |
---|---|
-1 to 1 |
hertz |
BATT7_FL_PIN: Fuel level analog pin number¶
Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT7_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATT8_ Parameters¶
BATT8_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT8_SERIAL_NUM: Battery serial number¶
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
BATT8_LOW_TIMER: Low voltage timeout¶
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 120 |
seconds |
BATT8_FS_VOLTSRC: Failsafe voltage source¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
BATT8_LOW_VOLT: Low battery voltage¶
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT8_LOW_MAH: Low battery capacity¶
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT8_CRT_VOLT: Critical battery voltage¶
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_CRT_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT8_CRT_MAH: Battery critical capacity¶
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8__FS_CRT_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT8_FS_LOW_ACT: Low battery failsafe action¶
What action the vehicle should perform if it hits a low battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_ARM_VOLT: Required arming voltage¶
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Increment |
Units |
---|---|
0.1 |
volt |
BATT8_ARM_MAH: Required arming remaining capacity¶
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT8__ARM_VOLT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT8_OPTIONS: Battery monitor options¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_VOLT_PIN: Battery Voltage sensing pin¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_VOLT_MULT: Voltage Multiplier¶
Used to convert the voltage of the voltage sensing pin (BATT8_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT8_AMP_PERVLT: Amps per volt¶
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
Units |
---|
ampere per volt |
BATT8_AMP_OFFSET: AMP offset¶
Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.
Units |
---|
volt |
BATT8_VLT_OFFSET: Voltage offset¶
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
Units |
---|
volt |
BATT8_I2C_BUS: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT8_I2C_ADDR: Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATT8_SUM_MASK: Battery Sum mask¶
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_CURR_MULT: Scales reported power monitor current¶
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
Range |
---|
.1 to 10 |
BATT8_FL_VLT_MIN: Empty fuel level voltage¶
The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
Units |
---|---|
0.01 to 10 |
volt |
BATT8_FL_V_MULT: Fuel level voltage multiplier¶
Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
---|
0.01 to 10 |
BATT8_FL_FLTR: Fuel level filter frequency¶
Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.
Range |
Units |
---|---|
-1 to 1 |
hertz |
BATT8_FL_PIN: Fuel level analog pin number¶
Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT8_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATT9_ Parameters¶
BATT9_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT9_SERIAL_NUM: Battery serial number¶
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.
BATT9_LOW_TIMER: Low voltage timeout¶
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 120 |
seconds |
BATT9_FS_VOLTSRC: Failsafe voltage source¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
BATT9_LOW_VOLT: Low battery voltage¶
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT9_LOW_MAH: Low battery capacity¶
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT9_CRT_VOLT: Critical battery voltage¶
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_CRT_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT9_CRT_MAH: Battery critical capacity¶
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9__FS_CRT_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT9_FS_LOW_ACT: Low battery failsafe action¶
What action the vehicle should perform if it hits a low battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_ARM_VOLT: Required arming voltage¶
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Increment |
Units |
---|---|
0.1 |
volt |
BATT9_ARM_MAH: Required arming remaining capacity¶
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT9__ARM_VOLT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT9_OPTIONS: Battery monitor options¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_VOLT_PIN: Battery Voltage sensing pin¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_VOLT_MULT: Voltage Multiplier¶
Used to convert the voltage of the voltage sensing pin (BATT9_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT9_AMP_PERVLT: Amps per volt¶
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
Units |
---|
ampere per volt |
BATT9_AMP_OFFSET: AMP offset¶
Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.
Units |
---|
volt |
BATT9_VLT_OFFSET: Voltage offset¶
Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.
Units |
---|
volt |
BATT9_I2C_BUS: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT9_I2C_ADDR: Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATT9_SUM_MASK: Battery Sum mask¶
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_CURR_MULT: Scales reported power monitor current¶
Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
Range |
---|
.1 to 10 |
BATT9_FL_VLT_MIN: Empty fuel level voltage¶
The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
Units |
---|---|
0.01 to 10 |
volt |
BATT9_FL_V_MULT: Fuel level voltage multiplier¶
Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.
Range |
---|
0.01 to 10 |
BATT9_FL_FLTR: Fuel level filter frequency¶
Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.
Range |
Units |
---|---|
-1 to 1 |
hertz |
BATT9_FL_PIN: Fuel level analog pin number¶
Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT9_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BATT_ Parameters¶
BATT_MONITOR: Battery monitoring¶
Controls enabling monitoring of the battery's voltage and current
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_CAPACITY: Battery capacity¶
Capacity of the battery in mAh when full
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT_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.
BATT_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 |
BATT_FS_VOLTSRC: Failsafe voltage source¶
Voltage type used for detection of low voltage event
Values |
||||||
---|---|---|---|---|---|---|
|
BATT_LOW_VOLT: Low battery voltage¶
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT_LOW_MAH: Low battery capacity¶
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT_CRT_VOLT: Critical battery voltage¶
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_CRT_ACT parameter.
Increment |
Units |
---|---|
0.1 |
volt |
BATT_CRT_MAH: Battery critical capacity¶
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT__FS_CRT_ACT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT_FS_LOW_ACT: Low battery failsafe action¶
What action the vehicle should perform if it hits a low battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_FS_CRT_ACT: Critical battery failsafe action¶
What action the vehicle should perform if it hits a critical battery failsafe
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_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 |
BATT_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 BATT__ARM_VOLT parameter.
Increment |
Units |
---|---|
50 |
milliampere hour |
BATT_OPTIONS: Battery monitor options¶
This sets options to change the behaviour of the battery monitor
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_VOLT_PIN: Battery Voltage sensing pin¶
Sets the analog input pin that should be used for voltage monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_CURR_PIN: Battery Current sensing pin¶
Sets the analog input pin that should be used for current monitoring.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_VOLT_MULT: Voltage Multiplier¶
Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
BATT_AMP_PERVLT: Amps per volt¶
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.
Units |
---|
ampere per volt |
BATT_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 |
BATT_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 |
BATT_I2C_BUS: Battery monitor I2C bus number¶
Battery monitor I2C bus number
Range |
---|
0 to 3 |
BATT_I2C_ADDR: Battery monitor I2C address¶
Battery monitor I2C address
Range |
---|
0 to 127 |
BATT_SUM_MASK: Battery Sum mask¶
0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
Bitmask |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_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 |
BATT_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 |
BATT_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 |
BATT_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 |
BATT_FL_PIN: Fuel level analog pin number¶
Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BATT_MAX_VOLT: Maximum Battery Voltage¶
Maximum voltage of battery. Provides scaling of current versus voltage
Range |
---|
7 to 100 |
BCN Parameters¶
BCN_TYPE: Beacon based position estimation device type¶
What type of beacon based position estimation device is connected
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BCN_LATITUDE: Beacon origin's latitude¶
Beacon origin's latitude
Increment |
Range |
Units |
---|---|---|
0.000001 |
-90 to 90 |
degrees |
BCN_LONGITUDE: Beacon origin's longitude¶
Beacon origin's longitude
Increment |
Range |
Units |
---|---|---|
0.000001 |
-180 to 180 |
degrees |
BCN_ALT: Beacon origin's altitude above sealevel in meters¶
Beacon origin's altitude above sealevel in meters
Increment |
Range |
Units |
---|---|---|
1 |
0 to 10000 |
meters |
BCN_ORIENT_YAW: Beacon systems rotation from north in degrees¶
Beacon systems rotation from north in degrees
Increment |
Range |
Units |
---|---|---|
1 |
-180 to +180 |
degrees |
BRD_ Parameters¶
BRD_SER1_RTSCTS: Serial 1 flow control¶
Enable flow control on serial 1 (telemetry 1). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_SER2_RTSCTS: Serial 2 flow control¶
Enable flow control on serial 2 (telemetry 2). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_SER3_RTSCTS: Serial 3 flow control¶
Enable flow control on serial 3. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_SER4_RTSCTS: Serial 4 flow control¶
Enable flow control on serial 4. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_SER5_RTSCTS: Serial 5 flow control¶
Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_SAFETY_DEFLT: Sets default state of the safety switch¶
This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
Values |
||||||
---|---|---|---|---|---|---|
|
BRD_SBUS_OUT: SBUS output rate¶
This sets the SBUS output frame rate in Hz
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_SERIAL_NUM: User-defined serial number¶
User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
Range |
---|
-8388608 to 8388607 |
BRD_SAFETY_MASK: Outputs which ignore the safety switch state¶
A bitmask which controls what outputs can move while the safety switch has not been pressed
Bitmask |
||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_HEAT_TARG: Board heater temperature target¶
Board heater target temperature for boards with controllable heating units. DO NOT SET to -1 on the Cube. Set to -1 to disable the heater, please reboot after setting to -1.
Range |
Units |
---|---|
-1 to 80 |
degrees Celsius |
BRD_TYPE: Board type¶
This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
Values |
||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_IO_ENABLE: Enable IO co-processor¶
This allows for the IO co-processor on boards with an IOMCU to be disabled. Setting to 2 will enable the IOMCU but not attempt to update firmware on startup
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_VBUS_MIN: Autopilot board voltage requirement¶
Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
---|---|---|
0.1 |
4.0 to 5.5 |
volt |
BRD_VSERVO_MIN: Servo voltage requirement¶
Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
---|---|---|
0.1 |
3.3 to 12.0 |
volt |
BRD_SD_SLOWDOWN: microSD slowdown¶
This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
Increment |
Range |
---|---|
1 |
0 to 32 |
BRD_PWM_VOLT_SEL: Set PWM Out Voltage¶
This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxilliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs.
Values |
||||||
---|---|---|---|---|---|---|
|
BRD_OPTIONS: Board options¶
Board specific option flags
Bitmask |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_BOOT_DELAY: Boot delay¶
This adds a delay in milliseconds to boot to ensure peripherals initialise fully
Range |
Units |
---|---|
0 to 10000 |
milliseconds |
BRD_HEAT_P: Board Heater P gain¶
Board Heater P gain
Increment |
Range |
---|---|
1 |
1 to 500 |
BRD_HEAT_I: Board Heater I gain¶
Board Heater integrator gain
Increment |
Range |
---|---|
0.1 |
0 to 1 |
BRD_HEAT_IMAX: Board Heater IMAX¶
Board Heater integrator maximum
Increment |
Range |
---|---|
1 |
0 to 100 |
BRD_ALT_CONFIG: Alternative HW config¶
Select an alternative hardware configuration. A value of zero selects the default configuration for this board. Other values are board specific. Please see the documentation for your board for details on any alternative configuration values that may be available.
Increment |
Range |
---|---|
1 |
0 to 10 |
BRD_HEAT_LOWMGN: Board heater temp lower margin¶
Arming check will fail if temp is lower than this margin below BRD_HEAT_TARG. 0 disables the low temperature check
Range |
Units |
---|---|
0 to 20 |
degrees Celsius |
BRD_SD_MISSION: SDCard Mission size¶
This sets the amount of storage in kilobytes reserved on the microsd card in mission.stg for waypoint storage. Each waypoint uses 15 bytes.
Range |
---|
0 to 64 |
BRD_RADIO Parameters¶
BRD_RADIO_TYPE: Set type of direct attached radio¶
This enables support for direct attached radio receivers
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
BRD_RADIO_PROT: protocol¶
Select air protocol
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_RADIO_DEBUG: debug level¶
radio debug level
Range |
---|
0 to 4 |
BRD_RADIO_DISCRC: disable receive CRC¶
disable receive CRC (for debug)
Values |
||||||
---|---|---|---|---|---|---|
|
BRD_RADIO_SIGCH: RSSI signal strength¶
Channel to show receive RSSI signal strength, or zero for disabled
Range |
---|
0 to 16 |
BRD_RADIO_PPSCH: Packet rate channel¶
Channel to show received packet-per-second rate, or zero for disabled
Range |
---|
0 to 16 |
BRD_RADIO_TELEM: Enable telemetry¶
If this is non-zero then telemetry packets will be sent over DSM
Values |
||||||
---|---|---|---|---|---|---|
|
BRD_RADIO_TXPOW: Telemetry Transmit power¶
Set telemetry transmit power. This is the power level (from 1 to 8) for telemetry packets sent from the RX to the TX
Range |
---|
1 to 8 |
BRD_RADIO_FCCTST: Put radio into FCC test mode¶
If this is enabled then the radio will continuously transmit as required for FCC testing. The transmit channel is set by the value of the parameter. The radio will not work for RC input while this is enabled
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_RADIO_STKMD: Stick input mode¶
This selects between different stick input modes. The default is mode2, which has throttle on the left stick and pitch on the right stick. You can instead set mode1, which has throttle on the right stick and pitch on the left stick.
Values |
||||||
---|---|---|---|---|---|---|
|
BRD_RADIO_TESTCH: Set radio to factory test channel¶
This sets the radio to a fixed test channel for factory testing. Using a fixed channel avoids the need for binding in factory testing.
Values |
||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
BRD_RADIO_TSIGCH: RSSI value channel for telemetry data on transmitter¶
Channel to show telemetry RSSI value as received by TX
Range |
---|
0 to 16 |
BRD_RADIO_TPPSCH: Telemetry PPS channel¶
Channel to show telemetry packets-per-second value, as received at TX
Range |
---|
0 to 16 |
BRD_RADIO_TXMAX: Transmitter transmit power¶
Set transmitter maximum transmit power (from 1 to 8)
Range |
---|
1 to 8 |
BRD_RADIO_BZOFS: Transmitter buzzer adjustment¶
Set transmitter buzzer note adjustment (adjust frequency up)
Range |
---|
0 to 40 |
BRD_RADIO_ABTIME: Auto-bind time¶
When non-zero this sets the time with no transmitter packets before we start looking for auto-bind packets.
Range |
---|
0 to 120 |
BRD_RADIO_ABLVL: Auto-bind level¶
This sets the minimum RSSI of an auto-bind packet for it to be accepted. This should be set so that auto-bind will only happen at short range to minimise the change of an auto-bind happening accidentially
Range |
---|
0 to 31 |
BRD_RTC Parameters¶
BRD_RTC_TYPES: Allowed sources of RTC time¶
Specifies which sources of UTC time will be accepted
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
BRD_RTC_TZ_MIN: Timezone offset from UTC¶
Adds offset in +- minutes from UTC to calculate local time
Range |
---|
-720 to +840 |
BTN_ Parameters¶
BTN_REPORT_SEND: Report send time¶
The duration in seconds that a BUTTON_CHANGE report is repeatedly sent to the GCS regarding a button changing state. Note that the BUTTON_CHANGE message is MAVLink2 only.
Range |
---|
0 to 3600 |
CAM Parameters¶
CAM_MAX_ROLL: Maximum photo roll angle.¶
Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
Range |
Units |
---|---|
0 to 180 |
degrees |
CAM_AUTO_ONLY: Distance-trigging in AUTO mode only¶
When enabled, trigging by distance is done in AUTO mode only.
Values |
||||||
---|---|---|---|---|---|---|
|
CAM1 Parameters¶
CAM1_TYPE: Camera shutter (trigger) type¶
how to trigger the camera to take a picture
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM1_DURATION: Camera shutter duration held open¶
Duration in seconds that the camera shutter is held open
Range |
Units |
---|---|
0 to 5 |
seconds |
CAM1_SERVO_ON: Camera servo ON PWM value¶
PWM value in microseconds to move servo to when shutter is activated
Range |
Units |
---|---|
1000 to 2000 |
PWM in microseconds |
CAM1_SERVO_OFF: Camera servo OFF PWM value¶
PWM value in microseconds to move servo to when shutter is deactivated
Range |
Units |
---|---|
1000 to 2000 |
PWM in microseconds |
CAM1_TRIGG_DIST: Camera trigger distance¶
Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
Range |
Units |
---|---|
0 to 1000 |
meters |
CAM1_RELAY_ON: Camera relay ON value¶
This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
Values |
||||||
---|---|---|---|---|---|---|
|
CAM1_INTRVAL_MIN: Camera minimum time interval between photos¶
Postpone shooting if previous picture was taken less than this many seconds ago
Range |
Units |
---|---|
0 to 10 |
seconds |
CAM1_FEEDBAK_PIN: Camera feedback pin¶
pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. See also the CAMx_FEEDBCK_POL option.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM1_FEEDBAK_POL: Camera feedback pin polarity¶
Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
Values |
||||||
---|---|---|---|---|---|---|
|
CAM2 Parameters¶
CAM2_TYPE: Camera shutter (trigger) type¶
how to trigger the camera to take a picture
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM2_DURATION: Camera shutter duration held open¶
Duration in seconds that the camera shutter is held open
Range |
Units |
---|---|
0 to 5 |
seconds |
CAM2_SERVO_ON: Camera servo ON PWM value¶
PWM value in microseconds to move servo to when shutter is activated
Range |
Units |
---|---|
1000 to 2000 |
PWM in microseconds |
CAM2_SERVO_OFF: Camera servo OFF PWM value¶
PWM value in microseconds to move servo to when shutter is deactivated
Range |
Units |
---|---|
1000 to 2000 |
PWM in microseconds |
CAM2_TRIGG_DIST: Camera trigger distance¶
Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
Range |
Units |
---|---|
0 to 1000 |
meters |
CAM2_RELAY_ON: Camera relay ON value¶
This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
Values |
||||||
---|---|---|---|---|---|---|
|
CAM2_INTRVAL_MIN: Camera minimum time interval between photos¶
Postpone shooting if previous picture was taken less than this many seconds ago
Range |
Units |
---|---|
0 to 10 |
seconds |
CAM2_FEEDBAK_PIN: Camera feedback pin¶
pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. See also the CAMx_FEEDBCK_POL option.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM2_FEEDBAK_POL: Camera feedback pin polarity¶
Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
Values |
||||||
---|---|---|---|---|---|---|
|
CAM_RC_ Parameters¶
CAM_RC_TYPE: RunCam device type¶
RunCam deviee type used to determine OSD menu structure and shutter options.
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM_RC_FEATURES: RunCam features available¶
The available features of the attached RunCam device. If 0 then the RunCam device will be queried for the features it supports, otherwise this setting is used.
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAM_RC_BT_DELAY: RunCam boot delay before allowing updates¶
Time it takes for the RunCam to become fully ready in ms. If this is too short then commands can get out of sync.
CAM_RC_CONTROL: RunCam control option¶
Specifies the allowed actions required to enter the OSD menu and other option like autorecording
Bitmask |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_ Parameters¶
CAN_LOGLEVEL: Loglevel¶
Loglevel for recording initialisation and debug information from CAN Interface
Range |
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0 to 4 |
|
CAN_D1_ Parameters¶
CAN_D1_PROTOCOL: Enable use of specific protocol over virtual driver¶
Enabling this option starts selected protocol that will use this virtual driver
Values |
||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_KDE_ Parameters¶
CAN_D1_KDE_NPOLE: Number of motor poles¶
Sets the number of motor poles to calculate the correct RPM value
CAN_D1_PC_ Parameters¶
CAN_D1_PC_ESC_BM: ESC channels¶
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_PC_ESC_RT: ESC output rate¶
Output rate of ESC command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D1_PC_SRV_BM: Servo channels¶
Bitmask defining which servo channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_PC_SRV_RT: Servo command output rate¶
Output rate of servo command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D1_PC_ECU_ID: ECU Node ID¶
Node ID to send ECU throttle messages to. Set to zero to disable ECU throttle messages. Set to 255 to broadcast to all ECUs.
Range |
---|
0 to 255 |
CAN_D1_PC_ECU_RT: ECU command output rate¶
Output rate of ECU command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D1_TST_ Parameters¶
CAN_D1_TST_ID: CAN Test Index¶
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Range |
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0 to 4 |
|
CAN_D1_TST_LPR8: CANTester LoopRate¶
Selects the Looprate of Test methods
Units |
---|
microseconds |
CAN_D1_UC_ Parameters¶
CAN_D1_UC_NODE: UAVCAN node that is used for this network¶
UAVCAN node should be set implicitly
Range |
---|
1 to 250 |
CAN_D1_UC_SRV_BM: Output channels to be transmitted as servo over UAVCAN¶
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_UC_ESC_BM: Output channels to be transmitted as ESC over UAVCAN¶
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_UC_SRV_RT: Servo output rate¶
Maximum transmit rate for servo outputs
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D1_UC_OPTION: UAVCAN options¶
Option flags
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D1_UC_NTF_RT: Notify State rate¶
Maximum transmit rate for Notify State Message
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D1_UC_ESC_OF: ESC Output channels offset¶
Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth
Range |
---|
0 to 18 |
CAN_D1_UC_POOL: CAN pool size¶
Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads
Range |
---|
1024 to 16384 |
CAN_D2_ Parameters¶
CAN_D2_PROTOCOL: Enable use of specific protocol over virtual driver¶
Enabling this option starts selected protocol that will use this virtual driver
Values |
||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_KDE_ Parameters¶
CAN_D2_KDE_NPOLE: Number of motor poles¶
Sets the number of motor poles to calculate the correct RPM value
CAN_D2_PC_ Parameters¶
CAN_D2_PC_ESC_BM: ESC channels¶
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_PC_ESC_RT: ESC output rate¶
Output rate of ESC command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D2_PC_SRV_BM: Servo channels¶
Bitmask defining which servo channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_PC_SRV_RT: Servo command output rate¶
Output rate of servo command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D2_PC_ECU_ID: ECU Node ID¶
Node ID to send ECU throttle messages to. Set to zero to disable ECU throttle messages. Set to 255 to broadcast to all ECUs.
Range |
---|
0 to 255 |
CAN_D2_PC_ECU_RT: ECU command output rate¶
Output rate of ECU command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D2_TST_ Parameters¶
CAN_D2_TST_ID: CAN Test Index¶
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Range |
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0 to 4 |
|
CAN_D2_TST_LPR8: CANTester LoopRate¶
Selects the Looprate of Test methods
Units |
---|
microseconds |
CAN_D2_UC_ Parameters¶
CAN_D2_UC_NODE: UAVCAN node that is used for this network¶
UAVCAN node should be set implicitly
Range |
---|
1 to 250 |
CAN_D2_UC_SRV_BM: Output channels to be transmitted as servo over UAVCAN¶
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_UC_ESC_BM: Output channels to be transmitted as ESC over UAVCAN¶
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_UC_SRV_RT: Servo output rate¶
Maximum transmit rate for servo outputs
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D2_UC_OPTION: UAVCAN options¶
Option flags
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D2_UC_NTF_RT: Notify State rate¶
Maximum transmit rate for Notify State Message
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D2_UC_ESC_OF: ESC Output channels offset¶
Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth
Range |
---|
0 to 18 |
CAN_D2_UC_POOL: CAN pool size¶
Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads
Range |
---|
1024 to 16384 |
CAN_D3_ Parameters¶
CAN_D3_PROTOCOL: Enable use of specific protocol over virtual driver¶
Enabling this option starts selected protocol that will use this virtual driver
Values |
||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_KDE_ Parameters¶
CAN_D3_KDE_NPOLE: Number of motor poles¶
Sets the number of motor poles to calculate the correct RPM value
CAN_D3_PC_ Parameters¶
CAN_D3_PC_ESC_BM: ESC channels¶
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_PC_ESC_RT: ESC output rate¶
Output rate of ESC command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D3_PC_SRV_BM: Servo channels¶
Bitmask defining which servo channels are to be transmitted over Piccolo CAN
Bitmask |
||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_PC_SRV_RT: Servo command output rate¶
Output rate of servo command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D3_PC_ECU_ID: ECU Node ID¶
Node ID to send ECU throttle messages to. Set to zero to disable ECU throttle messages. Set to 255 to broadcast to all ECUs.
Range |
---|
0 to 255 |
CAN_D3_PC_ECU_RT: ECU command output rate¶
Output rate of ECU command messages
Range |
Units |
---|---|
1 to 500 |
hertz |
CAN_D3_TST_ Parameters¶
CAN_D3_TST_ID: CAN Test Index¶
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Range |
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0 to 4 |
|
CAN_D3_TST_LPR8: CANTester LoopRate¶
Selects the Looprate of Test methods
Units |
---|
microseconds |
CAN_D3_UC_ Parameters¶
CAN_D3_UC_NODE: UAVCAN node that is used for this network¶
UAVCAN node should be set implicitly
Range |
---|
1 to 250 |
CAN_D3_UC_SRV_BM: Output channels to be transmitted as servo over UAVCAN¶
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_UC_ESC_BM: Output channels to be transmitted as ESC over UAVCAN¶
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Bitmask |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_UC_SRV_RT: Servo output rate¶
Maximum transmit rate for servo outputs
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D3_UC_OPTION: UAVCAN options¶
Option flags
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_D3_UC_NTF_RT: Notify State rate¶
Maximum transmit rate for Notify State Message
Range |
Units |
---|---|
1 to 200 |
hertz |
CAN_D3_UC_ESC_OF: ESC Output channels offset¶
Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth
Range |
---|
0 to 18 |
CAN_D3_UC_POOL: CAN pool size¶
Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads
Range |
---|
1024 to 16384 |
CAN_P1_ Parameters¶
CAN_P1_DRIVER: Index of virtual driver to be used with physical CAN interface¶
Enabling this option enables use of CAN buses.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
CAN_P1_BITRATE: Bitrate of CAN interface¶
Bit rate can be set up to from 10000 to 1000000
Range |
---|
10000 to 1000000 |
CAN_P1_FDBITRATE: Bitrate of CANFD interface¶
Bit rate can be set up to from 1000000 to 8000000
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_P2_ Parameters¶
CAN_P2_DRIVER: Index of virtual driver to be used with physical CAN interface¶
Enabling this option enables use of CAN buses.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
CAN_P2_BITRATE: Bitrate of CAN interface¶
Bit rate can be set up to from 10000 to 1000000
Range |
---|
10000 to 1000000 |
CAN_P2_FDBITRATE: Bitrate of CANFD interface¶
Bit rate can be set up to from 1000000 to 8000000
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_P3_ Parameters¶
CAN_P3_DRIVER: Index of virtual driver to be used with physical CAN interface¶
Enabling this option enables use of CAN buses.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
CAN_P3_BITRATE: Bitrate of CAN interface¶
Bit rate can be set up to from 10000 to 1000000
Range |
---|
10000 to 1000000 |
CAN_P3_FDBITRATE: Bitrate of CANFD interface¶
Bit rate can be set up to from 1000000 to 8000000
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_SLCAN_ Parameters¶
CAN_SLCAN_CPORT: SLCAN Route¶
CAN Interface ID to be routed to SLCAN, 0 means no routing
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
CAN_SLCAN_SERNUM: SLCAN Serial Port¶
Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial. This parameter is automatically reset on reboot or on timeout. See CAN_SLCAN_TIMOUT for timeout details
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CAN_SLCAN_TIMOUT: SLCAN Timeout¶
Duration of inactivity after which SLCAN is switched back to original driver in seconds.
Range |
---|
0 to 127 |
CAN_SLCAN_SDELAY: SLCAN Start Delay¶
Duration after which slcan starts after setting SERNUM in seconds.
Range |
---|
0 to 127 |
CC Parameters¶
CC_TYPE: Custom control type¶
Custom control type to be used
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
CC_AXIS_MASK: Custom Controller bitmask¶
Custom Controller bitmask to chose which axis to run
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
CHUTE_ Parameters¶
CHUTE_ENABLED: Parachute release enabled or disabled¶
Parachute release enabled or disabled
Values |
||||||
---|---|---|---|---|---|---|
|
CHUTE_TYPE: Parachute release mechanism type (relay or servo)¶
Parachute release mechanism type (relay or servo)
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
CHUTE_SERVO_ON: Parachute Servo ON PWM value¶
Parachute Servo PWM value in microseconds when parachute is released
Increment |
Range |
Units |
---|---|---|
1 |
1000 to 2000 |
PWM in microseconds |
CHUTE_SERVO_OFF: Servo OFF PWM value¶
Parachute Servo PWM value in microseconds when parachute is not released
Increment |
Range |
Units |
---|---|---|
1 |
1000 to 2000 |
PWM in microseconds |
CHUTE_ALT_MIN: Parachute min altitude in meters above home¶
Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 32000 |
meters |
CHUTE_DELAY_MS: Parachute release delay¶
Delay in millseconds between motor stop and chute release
Increment |
Range |
Units |
---|---|---|
1 |
0 to 5000 |
milliseconds |
CHUTE_CRT_SINK: Critical sink speed rate in m/s to trigger emergency parachute¶
Release parachute when critical sink rate is reached
Increment |
Range |
Units |
---|---|---|
1 |
0 to 15 |
meters per second |
CHUTE_OPTIONS: Parachute options¶
Optional behaviour for parachute
Bitmask |
||||
---|---|---|---|---|
|
CIRCLE_ Parameters¶
CIRCLE_RADIUS: Circle Radius¶
Defines the radius of the circle the vehicle will fly when in Circle flight mode
Increment |
Range |
Units |
---|---|---|
100 |
0 to 200000 |
centimeters |
CIRCLE_RATE: Circle rate¶
Circle mode's turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise. Circle rate must be less than ATC_SLEW_YAW parameter.
Increment |
Range |
Units |
---|---|---|
1 |
-90 to 90 |
degrees per second |
CIRCLE_OPTIONS: Circle options¶
0:Enable or disable using the pitch/roll stick control circle mode's radius and rate
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
COMPASS_ Parameters¶
COMPASS_OFS_X: Compass offsets in milligauss on the X axis¶
Offset to be added to the compass x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS_Y: Compass offsets in milligauss on the Y axis¶
Offset to be added to the compass y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS_Z: Compass offsets in milligauss on the Z axis¶
Offset to be added to the compass z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
---|---|---|
1 |
-400 to 400 |
milligauss |
COMPASS_DEC: Compass declination¶
An angle to compensate between the true north and magnetic north
Increment |
Range |
Units |
---|---|---|
0.01 |
-3.142 to 3.142 |
radians |
COMPASS_LEARN: Learn compass offsets automatically¶
Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_USE: Use compass for yaw¶
Enable or disable the use of the compass (instead of the GPS) for determining heading
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_AUTODEC: Auto Declination¶
Enable or disable the automatic calculation of the declination based on gps location
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_MOTCT: Motor interference compensation type¶
Set motor interference compensation type to disabled, throttle or current. Do not change manually.
Calibration |
Values |
||||||||
---|---|---|---|---|---|---|---|---|---|
1 |
|
COMPASS_MOT_X: Motor interference compensation for body frame X axis¶
Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT_Y: Motor interference compensation for body frame Y axis¶
Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT_Z: Motor interference compensation for body frame Z axis¶
Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
---|---|---|
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_ORIENT: Compass orientation¶
The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_EXTERNAL: Compass is attached via an external cable¶
Configure compass so it is attached externally. This is auto-detected on most boards. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
COMPASS_OFS2_X: Compass2 offsets in milligauss on the X axis¶
Offset to be added to compass2's x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS2_Y: Compass2 offsets in milligauss on the Y axis¶
Offset to be added to compass2's y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS2_Z: Compass2 offsets in milligauss on the Z axis¶
Offset to be added to compass2's z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
---|---|---|
1 |
-400 to 400 |
milligauss |
COMPASS_MOT2_X: Motor interference compensation to compass2 for body frame X axis¶
Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT2_Y: Motor interference compensation to compass2 for body frame Y axis¶
Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT2_Z: Motor interference compensation to compass2 for body frame Z axis¶
Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
---|---|---|
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_OFS3_X: Compass3 offsets in milligauss on the X axis¶
Offset to be added to compass3's x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS3_Y: Compass3 offsets in milligauss on the Y axis¶
Offset to be added to compass3's y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-400 to 400 |
milligauss |
COMPASS_OFS3_Z: Compass3 offsets in milligauss on the Z axis¶
Offset to be added to compass3's z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
---|---|---|
1 |
-400 to 400 |
milligauss |
COMPASS_MOT3_X: Motor interference compensation to compass3 for body frame X axis¶
Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT3_Y: Motor interference compensation to compass3 for body frame Y axis¶
Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
---|---|---|---|
1 |
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_MOT3_Z: Motor interference compensation to compass3 for body frame Z axis¶
Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
---|---|---|
1 |
-1000 to 1000 |
milligauss per ampere |
COMPASS_DEV_ID: Compass device id¶
Compass device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID2: Compass2 device id¶
Second compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID3: Compass3 device id¶
Third compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_USE2: Compass2 used for yaw¶
Enable or disable the secondary compass for determining heading.
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_ORIENT2: Compass2 orientation¶
The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_EXTERN2: Compass2 is attached via an external cable¶
Configure second compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
COMPASS_USE3: Compass3 used for yaw¶
Enable or disable the tertiary compass for determining heading.
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_ORIENT3: Compass3 orientation¶
The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
Values |
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_EXTERN3: Compass3 is attached via an external cable¶
Configure third compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
COMPASS_DIA_X: Compass soft-iron diagonal X component¶
DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA_Y: Compass soft-iron diagonal Y component¶
DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA_Z: Compass soft-iron diagonal Z component¶
DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI_X: Compass soft-iron off-diagonal X component¶
ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI_Y: Compass soft-iron off-diagonal Y component¶
ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI_Z: Compass soft-iron off-diagonal Z component¶
ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA2_X: Compass2 soft-iron diagonal X component¶
DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA2_Y: Compass2 soft-iron diagonal Y component¶
DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA2_Z: Compass2 soft-iron diagonal Z component¶
DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI2_X: Compass2 soft-iron off-diagonal X component¶
ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI2_Y: Compass2 soft-iron off-diagonal Y component¶
ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI2_Z: Compass2 soft-iron off-diagonal Z component¶
ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_DIA3_X: Compass3 soft-iron diagonal X component¶
DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA3_Y: Compass3 soft-iron diagonal Y component¶
DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_DIA3_Z: Compass3 soft-iron diagonal Z component¶
DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_ODI3_X: Compass3 soft-iron off-diagonal X component¶
ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI3_Y: Compass3 soft-iron off-diagonal Y component¶
ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
Calibration |
---|
1 |
COMPASS_ODI3_Z: Compass3 soft-iron off-diagonal Z component¶
ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
COMPASS_CAL_FIT: Compass calibration fitness¶
This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
Increment |
Range |
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
0.1 |
4 to 32 |
|
COMPASS_OFFS_MAX: Compass maximum offset¶
This sets the maximum allowed compass offset in calibration and arming checks
Increment |
Range |
---|---|
1 |
500 to 3000 |
COMPASS_TYPEMASK: Compass disable driver type mask¶
This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
Bitmask |
||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_FLTR_RNG: Range in which sample is accepted¶
This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
Increment |
Range |
Units |
---|---|---|
1 |
0 to 100 |
percent |
COMPASS_AUTO_ROT: Automatically check orientation¶
When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
COMPASS_PRIO1_ID: Compass device id with 1st order priority¶
Compass device id with 1st order priority, set automatically if 0. Reboot required after change.
COMPASS_PRIO2_ID: Compass device id with 2nd order priority¶
Compass device id with 2nd order priority, set automatically if 0. Reboot required after change.
COMPASS_PRIO3_ID: Compass device id with 3rd order priority¶
Compass device id with 3rd order priority, set automatically if 0. Reboot required after change.
COMPASS_ENABLE: Enable Compass¶
Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_SCALE: Compass1 scale factor¶
Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
Range |
---|
0 to 1.3 |
COMPASS_SCALE2: Compass2 scale factor¶
Scaling factor for 2nd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
Range |
---|
0 to 1.3 |
COMPASS_SCALE3: Compass3 scale factor¶
Scaling factor for 3rd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
Range |
---|
0 to 1.3 |
COMPASS_OPTIONS: Compass options¶
This sets options to change the behaviour of the compass
Bitmask |
||||
---|---|---|---|---|
|
COMPASS_DEV_ID4: Compass4 device id¶
Extra 4th compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID5: Compass5 device id¶
Extra 5th compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID6: Compass6 device id¶
Extra 6th compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID7: Compass7 device id¶
Extra 7th compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_DEV_ID8: Compass8 device id¶
Extra 8th compass's device id. Automatically detected, do not set manually
ReadOnly |
---|
True |
COMPASS_CUS_ROLL: Custom orientation roll offset¶
Compass mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
Increment |
Range |
Units |
---|---|---|
1 |
-180 to 180 |
degrees |
COMPASS_CUS_PIT: Custom orientation pitch offset¶
Compass mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
Increment |
Range |
Units |
---|---|---|
1 |
-180 to 180 |
degrees |
COMPASS_CUS_YAW: Custom orientation yaw offset¶
Compass mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
Increment |
Range |
Units |
---|---|---|
1 |
-180 to 180 |
degrees |
COMPASS_PMOT Parameters¶
COMPASS_PMOT_EN: per-motor compass correction enable¶
This enables per-motor compass corrections
Values |
||||||
---|---|---|---|---|---|---|
|
COMPASS_PMOT_EXP: per-motor exponential correction¶
This is the exponential correction for the power output of the motor for per-motor compass correction
Increment |
Range |
---|---|
0.01 |
0 to 2 |
COMPASS_PMOT1_X: Compass per-motor1 X¶
Compensation for X axis of motor1
COMPASS_PMOT1_Y: Compass per-motor1 Y¶
Compensation for Y axis of motor1
COMPASS_PMOT1_Z: Compass per-motor1 Z¶
Compensation for Z axis of motor1
COMPASS_PMOT2_X: Compass per-motor2 X¶
Compensation for X axis of motor2
COMPASS_PMOT2_Y: Compass per-motor2 Y¶
Compensation for Y axis of motor2
COMPASS_PMOT2_Z: Compass per-motor2 Z¶
Compensation for Z axis of motor2
COMPASS_PMOT3_X: Compass per-motor3 X¶
Compensation for X axis of motor3
COMPASS_PMOT3_Y: Compass per-motor3 Y¶
Compensation for Y axis of motor3
COMPASS_PMOT3_Z: Compass per-motor3 Z¶
Compensation for Z axis of motor3
COMPASS_PMOT4_X: Compass per-motor4 X¶
Compensation for X axis of motor4
COMPASS_PMOT4_Y: Compass per-motor4 Y¶
Compensation for Y axis of motor4
COMPASS_PMOT4_Z: Compass per-motor4 Z¶
Compensation for Z axis of motor4
CUST_ROT Parameters¶
CUST_ROT_ENABLE: Enable Custom rotations¶
This enables custom rotations
Values |
||||||
---|---|---|---|---|---|---|
|
CUST_ROT1_ Parameters¶
CUST_ROT1_ROLL: Custom roll¶
Custom euler roll, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
CUST_ROT1_PITCH: Custom pitch¶
Custom euler pitch, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
CUST_ROT1_YAW: Custom yaw¶
Custom euler yaw, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
CUST_ROT2_ Parameters¶
CUST_ROT2_ROLL: Custom roll¶
Custom euler roll, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
CUST_ROT2_PITCH: Custom pitch¶
Custom euler pitch, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
CUST_ROT2_YAW: Custom yaw¶
Custom euler yaw, euler 321 (yaw, pitch, roll) ordering
Units |
---|
degrees |
DID_ Parameters¶
DID_ENABLE: Enable ODID subsystem¶
Enable ODID subsystem
Values |
||||||
---|---|---|---|---|---|---|
|
DID_MAVPORT: MAVLink serial port¶
Serial port number to send OpenDroneID MAVLink messages to. Can be -1 if using DroneCAN.
Values |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
DID_CANDRIVER: DroneCAN driver number¶
DroneCAN driver index, 0 to disable DroneCAN
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
DID_OPTIONS: OpenDroneID options¶
Options for OpenDroneID subsystem
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
DID_BARO_ACC: Barometer vertical accuraacy¶
Barometer Vertical Accuracy when installed in the vehicle. Note this is dependent upon installation conditions and thus disabled by default
Units |
---|
meters |
EAHRS Parameters¶
EAHRS_TYPE: AHRS type¶
Type of AHRS device
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
EAHRS_RATE: AHRS data rate¶
Requested rate for AHRS device
Units |
---|
hertz |
EAHRS_OPTIONS: External AHRS options¶
External AHRS options bitmask
Bitmask |
||||
---|---|---|---|---|
|
EAHRS_SENSORS: External AHRS sensors¶
External AHRS sensors bitmask
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
EFI Parameters¶
EFI_TYPE: EFI communication type¶
What method of communication is used for EFI #1
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EFI_COEF1: EFI Calibration Coefficient 1¶
Used to calibrate fuel flow for MS protocol (Slope). This should be calculated from a log at constant fuel usage rate. Plot (ECYL[0].InjT*EFI.Rpm)/600.0 to get the duty_cycle. Measure actual fuel usage in cm^3/min, and set EFI_COEF1 = fuel_usage_cm3permin / duty_cycle
Range |
---|
0 to 1 |
EFI_COEF2: EFI Calibration Coefficient 2¶
Used to calibrate fuel flow for MS protocol (Offset). This can be used to correct for a non-zero offset in the fuel consumption calculation of EFI_COEF1
Range |
---|
0 to 10 |
EFI_FUEL_DENS: ECU Fuel Density¶
Used to calculate fuel consumption
Range |
Units |
---|---|
0 to 10000 |
kilograms per cubic meter |
EK2_ Parameters¶
EK2_ENABLE: Enable EKF2¶
This enables EKF2. Enabling EKF2 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=2. A reboot or restart will need to be performed after changing the value of EK2_ENABLE for it to take effect.
Values |
||||||
---|---|---|---|---|---|---|
|
EK2_GPS_TYPE: GPS mode control¶
This controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = Inhibit GPS use - this can be useful when flying with an optical flow sensor in an environment where GPS quality is poor and subject to large multipath errors.
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
EK2_VELNE_M_NSE: GPS horizontal velocity measurement noise (m/s)¶
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 5.0 |
meters per second |
EK2_VELD_M_NSE: GPS vertical velocity measurement noise (m/s)¶
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 5.0 |
meters per second |
EK2_VEL_I_GATE: GPS velocity innovation gate size¶
This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_POSNE_M_NSE: GPS horizontal position measurement noise (m)¶
This sets the GPS horizontal position observation noise. Increasing it reduces the weighting of GPS horizontal position measurements.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK2_POS_I_GATE: GPS position measurement gate size¶
This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_GLITCH_RAD: GPS glitch radius gate size (m)¶
This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position.
Increment |
Range |
Units |
---|---|---|
5 |
10 to 100 |
meters |
EK2_ALT_SOURCE: Primary altitude sensor source¶
Primary height sensor used by the EKF. If a sensor other than Baro is selected and becomes unavailable, then the Baro sensor will be used as a fallback. NOTE: The EK2_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground in conjunction with EK2_ALT_SOURCE = 0 or 2 (Baro or GPS).
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
EK2_ALT_M_NSE: Altitude measurement noise (m)¶
This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK2_HGT_I_GATE: Height measurement gate size¶
This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_HGT_DELAY: Height measurement delay (msec)¶
This is the number of msec that the Height measurements lag behind the inertial measurements.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 250 |
milliseconds |
EK2_MAG_M_NSE: Magnetometer measurement noise (Gauss)¶
This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.01 to 0.5 |
gauss |
EK2_MAG_CAL: Magnetometer default fusion mode¶
This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states, when it will use a simpler magnetic heading fusion model that does not use magnetic field states and when it will use an alternative method of yaw determination to the magnetometer. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK2_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK2_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK2_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK2_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK2_MAG_CAL = 4 uses 3-axis fusion at all times. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK2_MAG_MASK parameter. NOTE: limited operation without a magnetometer or any other yaw sensor is possible by setting all COMPASS_USE, COMPASS_USE2, COMPASS_USE3, etc parameters to 0 with COMPASS_ENABLE set to 1. If this is done, the EK2_GSF_RUN and EK2_GSF_USE masks must be set to the same as EK2_IMU_MASK.
Values |
||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_MAG_I_GATE: Magnetometer measurement gate size¶
This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_EAS_M_NSE: Equivalent airspeed measurement noise (m/s)¶
This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 5.0 |
meters per second |
EK2_EAS_I_GATE: Airspeed measurement gate size¶
This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_RNG_M_NSE: Range finder measurement noise (m)¶
This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK2_RNG_I_GATE: Range finder measurement gate size¶
This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_MAX_FLOW: Maximum valid optical flow rate¶
This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
Increment |
Range |
Units |
---|---|---|
0.1 |
1.0 to 4.0 |
radians per second |
EK2_FLOW_M_NSE: Optical flow measurement noise (rad/s)¶
This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 1.0 |
radians per second |
EK2_FLOW_I_GATE: Optical Flow measurement gate size¶
This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_FLOW_DELAY: Optical Flow measurement delay (msec)¶
This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 127 |
milliseconds |
EK2_GYRO_P_NSE: Rate gyro noise (rad/s)¶
This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
Increment |
Range |
Units |
---|---|---|
0.0001 |
0.0001 to 0.1 |
radians per second |
EK2_ACC_P_NSE: Accelerometer noise (m/s^2)¶
This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.01 to 1.0 |
meters per square second |
EK2_GBIAS_P_NSE: Rate gyro bias stability (rad/s/s)¶
This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.001 |
radians per square second |
EK2_GSCL_P_NSE: Rate gyro scale factor stability (1/s)¶
This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier.
Range |
Units |
---|---|
0.000001 to 0.001 |
hertz |
EK2_ABIAS_P_NSE: Accelerometer bias stability (m/s^3)¶
This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.005 |
meters per cubic second |
EK2_WIND_P_NSE: Wind velocity process noise (m/s^2)¶
This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.01 to 1.0 |
meters per square second |
EK2_WIND_PSCALE: Height rate to wind process noise scaler¶
This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
Increment |
Range |
---|---|
0.1 |
0.0 to 1.0 |
EK2_GPS_CHECK: GPS preflight check¶
This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_IMU_MASK: Bitmask of active IMUs¶
1 byte bitmap of IMUs to use in EKF2. A separate instance of EKF2 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF2 will fail to start.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_CHECK_SCALE: GPS accuracy check scaler (%)¶
This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
Range |
Units |
---|---|
50 to 200 |
percent |
EK2_NOAID_M_NSE: Non-GPS operation position uncertainty (m)¶
This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
Range |
Units |
---|---|
0.5 to 50.0 |
meters |
EK2_YAW_M_NSE: Yaw measurement noise (rad)¶
This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 1.0 |
radians |
EK2_YAW_I_GATE: Yaw measurement gate size¶
This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_TAU_OUTPUT: Output complementary filter time constant (centi-sec)¶
Sets the time constant of the output complementary filter/predictor in centi-seconds.
Increment |
Range |
Units |
---|---|---|
5 |
10 to 50 |
centiseconds |
EK2_MAGE_P_NSE: Earth magnetic field process noise (gauss/s)¶
This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.01 |
gauss per second |
EK2_MAGB_P_NSE: Body magnetic field process noise (gauss/s)¶
This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.01 |
gauss per second |
EK2_RNG_USE_HGT: Range finder switch height percentage¶
Range finder can be used as the primary height source when below this percentage of its maximum range (see RNGFND_MAX_CM). This will not work unless Baro or GPS height is selected as the primary height source vis EK2_ALT_SOURCE = 0 or 2 respectively. This feature should not be used for terrain following as it is designed for vertical takeoff and landing with climb above the range finder use height before commencing the mission, and with horizontal position changes below that height being limited to a flat region around the takeoff and landing point.
Increment |
Range |
Units |
---|---|---|
1 |
-1 to 70 |
percent |
EK2_TERR_GRAD: Maximum terrain gradient¶
Specifies the maximum gradient of the terrain below the vehicle assumed when it is fusing range finder or optical flow to estimate terrain height.
Increment |
Range |
---|---|
0.01 |
0 to 0.2 |
EK2_BCN_M_NSE: Range beacon measurement noise (m)¶
This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK2_BCN_I_GTE: Range beacon measurement gate size¶
This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK2_BCN_DELAY: Range beacon measurement delay (msec)¶
This is the number of msec that the range beacon measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 127 |
milliseconds |
EK2_RNG_USE_SPD: Range finder max ground speed¶
The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
Increment |
Range |
Units |
---|---|---|
0.5 |
2.0 to 6.0 |
meters per second |
EK2_MAG_MASK: Bitmask of active EKF cores that will always use heading fusion¶
1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_OGN_HGT_MASK: Bitmask control of EKF reference height correction¶
When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
EK2_FLOW_USE: Optical flow use bitmask¶
Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
EK2_MAG_EF_LIM: EarthField error limit¶
This limits the difference between the learned earth magnetic field and the earth field from the world magnetic model tables. A value of zero means to disable the use of the WMM tables.
Range |
Units |
---|---|
0 to 500 |
milligauss |
EK2_HRT_FILT: Height rate filter crossover frequency¶
Specifies the crossover frequency of the complementary filter used to calculate the output predictor height rate derivative.
Range |
Units |
---|---|
0.1 to 30.0 |
hertz |
EK2_GSF_RUN_MASK: Bitmask of which EKF-GSF yaw estimators run¶
A bitmask of which EKF2 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF2 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK2_GSF_USE_MASK and EK2_GSF_RST_MAX parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK2_GSF_USE_MASK to 0.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_GSF_USE_MASK: Bitmask of which EKF-GSF yaw estimators are used¶
1 byte bitmap of which EKF2 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK2_GSF_RUN_MASK parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF2 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF2 instance.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK2_GSF_RST_MAX: Maximum number of resets to the EKF-GSF yaw estimate allowed¶
Sets the maximum number of times the EKF2 will be allowed to reset its yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE_MASK parameter.
Increment |
Range |
---|---|
1 |
1 to 10 |
EK3_ Parameters¶
EK3_ENABLE: Enable EKF3¶
This enables EKF3. Enabling EKF3 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=3. A reboot or restart will need to be performed after changing the value of EK3_ENABLE for it to take effect.
Values |
||||||
---|---|---|---|---|---|---|
|
EK3_VELNE_M_NSE: GPS horizontal velocity measurement noise (m/s)¶
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 5.0 |
meters per second |
EK3_VELD_M_NSE: GPS vertical velocity measurement noise (m/s)¶
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 5.0 |
meters per second |
EK3_VEL_I_GATE: GPS velocity innovation gate size¶
This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD set to 0 the velocity innovations will be clipped instead of rejected if they exceed the gate size and a smaller value of EK3_VEL_I_GATE not exceeding 300 is recommended to limit the effect of GPS transient errors.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_POSNE_M_NSE: GPS horizontal position measurement noise (m)¶
This sets the GPS horizontal position observation noise. Increasing it reduces the weighting of GPS horizontal position measurements.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK3_POS_I_GATE: GPS position measurement gate size¶
This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD has been set to 0 the horizontal position innovations will be clipped instead of rejected if they exceed the gate size so a smaller value of EK3_POS_I_GATE not exceeding 300 is recommended to limit the effect of GPS transient errors.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_GLITCH_RAD: GPS glitch radius gate size (m)¶
This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position. If EK3_GLITCH_RAD set to 0 the GPS innovations will be clipped instead of rejected if they exceed the gate size set by EK3_VEL_I_GATE and EK3_POS_I_GATE which can be useful if poor quality sensor data is causing GPS rejection and loss of navigation but does make the EKF more susceptible to GPS glitches. If setting EK3_GLITCH_RAD to 0 it is recommended to reduce EK3_VEL_I_GATE and EK3_POS_I_GATE to 300.
Increment |
Range |
Units |
---|---|---|
5 |
10 to 100 |
meters |
EK3_ALT_M_NSE: Altitude measurement noise (m)¶
This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors. A larger value for EK3_ALT_M_NSE may be required when operating with EK3_SRCx_POSZ = 0. This parameter also sets the noise for the 'synthetic' zero height measurement that is used when EK3_SRCx_POSZ = 0.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 100.0 |
meters |
EK3_HGT_I_GATE: Height measurement gate size¶
This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD set to 0 the vertical position innovations will be clipped instead of rejected if they exceed the gate size and a smaller value of EK3_HGT_I_GATE not exceeding 300 is recommended to limit the effect of height sensor transient errors.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_HGT_DELAY: Height measurement delay (msec)¶
This is the number of msec that the Height measurements lag behind the inertial measurements.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 250 |
milliseconds |
EK3_MAG_M_NSE: Magnetometer measurement noise (Gauss)¶
This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.01 to 0.5 |
gauss |
EK3_MAG_CAL: Magnetometer default fusion mode¶
This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states and when it will use a simpler magnetic heading fusion model that does not use magnetic field states. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK3_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK3_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK3_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK3_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK3_MAG_CAL = 4 uses 3-axis fusion at all times. EK3_MAG_CAL = 5 uses an external yaw sensor with simple heading fusion. NOTE : Use of simple heading magnetometer fusion makes vehicle compass calibration and alignment errors harder for the EKF to detect which reduces the sensitivity of the Copter EKF failsafe algorithm. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK3_MAG_MASK parameter. EK3_MAG_CAL = 6 uses an external yaw sensor with fallback to compass when the external sensor is not available if we are flying. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK3_MAG_MASK parameter. NOTE: limited operation without a magnetometer or any other yaw sensor is possible by setting all COMPASS_USE, COMPASS_USE2, COMPASS_USE3, etc parameters to 0 and setting COMPASS_ENABLE to 0. If this is done, the EK3_GSF_RUN and EK3_GSF_USE masks must be set to the same as EK3_IMU_MASK. A yaw angle derived from IMU and GPS velocity data using a Gaussian Sum Filter (GSF) will then be used to align the yaw when flight commences and there is sufficient movement.
Values |
||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_MAG_I_GATE: Magnetometer measurement gate size¶
This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_EAS_M_NSE: Equivalent airspeed measurement noise (m/s)¶
This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 5.0 |
meters per second |
EK3_EAS_I_GATE: Airspeed measurement gate size¶
This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_RNG_M_NSE: Range finder measurement noise (m)¶
This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK3_RNG_I_GATE: Range finder measurement gate size¶
This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_MAX_FLOW: Maximum valid optical flow rate¶
This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
Increment |
Range |
Units |
---|---|---|
0.1 |
1.0 to 4.0 |
radians per second |
EK3_FLOW_M_NSE: Optical flow measurement noise (rad/s)¶
This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 1.0 |
radians per second |
EK3_FLOW_I_GATE: Optical Flow measurement gate size¶
This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_FLOW_DELAY: Optical Flow measurement delay (msec)¶
This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 250 |
milliseconds |
EK3_GYRO_P_NSE: Rate gyro noise (rad/s)¶
This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
Increment |
Range |
Units |
---|---|---|
0.0001 |
0.0001 to 0.1 |
radians per second |
EK3_ACC_P_NSE: Accelerometer noise (m/s^2)¶
This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.01 to 1.0 |
meters per square second |
EK3_GBIAS_P_NSE: Rate gyro bias stability (rad/s/s)¶
This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.001 |
radians per square second |
EK3_ABIAS_P_NSE: Accelerometer bias stability (m/s^3)¶
This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.02 |
meters per cubic second |
EK3_WIND_P_NSE: Wind velocity process noise (m/s^2)¶
This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.01 to 2.0 |
meters per square second |
EK3_WIND_PSCALE: Height rate to wind process noise scaler¶
This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
Increment |
Range |
---|---|
0.1 |
0.0 to 2.0 |
EK3_GPS_CHECK: GPS preflight check¶
This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
Bitmask |
||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_IMU_MASK: Bitmask of active IMUs¶
1 byte bitmap of IMUs to use in EKF3. A separate instance of EKF3 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF3 will fail to start.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_CHECK_SCALE: GPS accuracy check scaler (%)¶
This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
Range |
Units |
---|---|
50 to 200 |
percent |
EK3_NOAID_M_NSE: Non-GPS operation position uncertainty (m)¶
This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
Range |
Units |
---|---|
0.5 to 50.0 |
meters |
EK3_BETA_MASK: Bitmask controlling sidelip angle fusion¶
1 byte bitmap controlling use of sideslip angle fusion for estimation of non wind states during operation of 'fly forward' vehicle types such as fixed wing planes. By assuming that the angle of sideslip is small, the wind velocity state estimates are corrected whenever the EKF is not dead reckoning (e.g. has an independent velocity or position sensor such as GPS). This behaviour is on by default and cannot be disabled. When the EKF is dead reckoning, the wind states are used as a reference, enabling use of the small angle of sideslip assumption to correct non wind velocity states (eg attitude, velocity, position, etc) and improve navigation accuracy. This behaviour is on by default and cannot be disabled. The behaviour controlled by this parameter is the use of the small angle of sideslip assumption to correct non wind velocity states when the EKF is NOT dead reckoning. This is primarily of benefit to reduce the buildup of yaw angle errors during straight and level flight without a yaw sensor (e.g. magnetometer or dual antenna GPS yaw) provided aerobatic flight maneuvers with large sideslip angles are not performed. The 'always' option might be used where the yaw sensor is intentionally not fitted or disabled. The 'WhenNoYawSensor' option might be used if a yaw sensor is fitted, but protection against in-flight failure and continual rejection by the EKF is desired. For vehicles operated within visual range of the operator performing frequent turning maneuvers, setting this parameter is unnecessary.
Bitmask |
||||||
---|---|---|---|---|---|---|
|
EK3_YAW_M_NSE: Yaw measurement noise (rad)¶
This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 1.0 |
radians |
EK3_YAW_I_GATE: Yaw measurement gate size¶
This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_TAU_OUTPUT: Output complementary filter time constant (centi-sec)¶
Sets the time constant of the output complementary filter/predictor in centi-seconds.
Increment |
Range |
Units |
---|---|---|
5 |
10 to 50 |
centiseconds |
EK3_MAGE_P_NSE: Earth magnetic field process noise (gauss/s)¶
This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.01 |
gauss per second |
EK3_MAGB_P_NSE: Body magnetic field process noise (gauss/s)¶
This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
Range |
Units |
---|---|
0.00001 to 0.01 |
gauss per second |
EK3_RNG_USE_HGT: Range finder switch height percentage¶
Range finder can be used as the primary height source when below this percentage of its maximum range (see RNGFNDx_MAX_CM) and the primary height source is Baro or GPS (see EK3_SRCx_POSZ). This feature should not be used for terrain following as it is designed for vertical takeoff and landing with climb above the range finder use height before commencing the mission, and with horizontal position changes below that height being limited to a flat region around the takeoff and landing point.
Increment |
Range |
Units |
---|---|---|
1 |
-1 to 70 |
percent |
EK3_TERR_GRAD: Maximum terrain gradient¶
Specifies the maximum gradient of the terrain below the vehicle when it is using range finder as a height reference
Increment |
Range |
---|---|
0.01 |
0 to 0.2 |
EK3_BCN_M_NSE: Range beacon measurement noise (m)¶
This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 10.0 |
meters |
EK3_BCN_I_GTE: Range beacon measurement gate size¶
This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
---|---|
25 |
100 to 1000 |
EK3_BCN_DELAY: Range beacon measurement delay (msec)¶
This is the number of msec that the range beacon measurements lag behind the inertial measurements.
Increment |
Range |
Units |
---|---|---|
10 |
0 to 250 |
milliseconds |
EK3_RNG_USE_SPD: Range finder max ground speed¶
The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
Increment |
Range |
Units |
---|---|---|
0.5 |
2.0 to 6.0 |
meters per second |
EK3_ACC_BIAS_LIM: Accelerometer bias limit¶
The accelerometer bias state will be limited to +- this value
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 2.5 |
meters per square second |
EK3_MAG_MASK: Bitmask of active EKF cores that will always use heading fusion¶
1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_OGN_HGT_MASK: Bitmask control of EKF reference height correction¶
When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
Bitmask |
||||||||
---|---|---|---|---|---|---|---|---|
|
EK3_VIS_VERR_MIN: Visual odometry minimum velocity error¶
This is the 1-STD odometry velocity observation error that will be assumed when maximum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
Increment |
Range |
Units |
---|---|---|
0.05 |
0.05 to 0.5 |
meters per second |
EK3_VIS_VERR_MAX: Visual odometry maximum velocity error¶
This is the 1-STD odometry velocity observation error that will be assumed when minimum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.5 to 5.0 |
meters per second |
EK3_WENC_VERR: Wheel odometry velocity error¶
This is the 1-STD odometry velocity observation error that will be assumed when wheel encoder data is being fused.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.01 to 1.0 |
meters per second |
EK3_FLOW_USE: Optical flow use bitmask¶
Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
Values |
||||||||
---|---|---|---|---|---|---|---|---|
|
EK3_HRT_FILT: Height rate filter crossover frequency¶
Specifies the crossover frequency of the complementary filter used to calculate the output predictor height rate derivative.
Range |
Units |
---|---|
0.1 to 30.0 |
hertz |
EK3_MAG_EF_LIM: EarthField error limit¶
This limits the difference between the learned earth magnetic field and the earth field from the world magnetic model tables. A value of zero means to disable the use of the WMM tables.
Range |
Units |
---|---|
0 to 500 |
milligauss |
EK3_GSF_RUN_MASK: Bitmask of which EKF-GSF yaw estimators run¶
1 byte bitmap of which EKF3 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF3 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK3_GSF_USE_MASK and EK3_GSF_RST_MAX parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK3_GSF_USE to 0.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_GSF_USE_MASK: Bitmask of which EKF-GSF yaw estimators are used¶
A bitmask of which EKF3 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK3_GSF_RUN_MASK parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF3 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF3 instance.
Bitmask |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_GSF_RST_MAX: Maximum number of resets to the EKF-GSF yaw estimate allowed¶
Sets the maximum number of times the EKF3 will be allowed to reset its yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK3_GSF_USE_MASK parameter.
Increment |
Range |
---|---|
1 |
1 to 10 |
EK3_ERR_THRESH: EKF3 Lane Relative Error Sensitivity Threshold¶
lanes have to be consistently better than the primary by at least this threshold to reduce their overall relativeCoreError, lowering this makes lane switching more sensitive to smaller error differences
Increment |
Range |
---|---|
0.05 |
0.05 to 1 |
EK3_AFFINITY: EKF3 Sensor Affinity Options¶
These options control the affinity between sensor instances and EKF cores
Bitmask |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
EK3_DRAG_BCOEF_X: Ballistic coefficient for X axis drag¶
Ratio of mass to drag coefficient measured along the X body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the frontal area. The predicted drag from the rotors is specified separately by the EK3_DRAG_MCOEF parameter.
Range |
Units |
---|---|
0.0 to 1000.0 |
kilograms per square meter |
EK3_DRAG_BCOEF_Y: Ballistic coefficient for Y axis drag¶
Ratio of mass to drag coefficient measured along the Y body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the side area. The predicted drag from the rotors is specified separately by the EK3_DRAG_MCOEF parameter.
Range |
Units |
---|---|
50.0 to 1000.0 |
kilograms per square meter |
EK3_DRAG_M_NSE: Observation noise for drag acceleration¶
This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters
Increment |
Range |
Units |
---|---|---|
0.1 |
0.1 to 2.0 |
meters per square second |
EK3_DRAG_MCOEF: Momentum coefficient for propeller drag¶
This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_DRAG_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters.
Increment |
Range |
Units |
---|---|---|
0.01 |
0.0 to 1.0 |
per second |
EK3_OGNM_TEST_SF: On ground not moving test scale factor¶
This parameter is adjust the sensitivity of the on ground not moving test which is used to assist with learning the yaw gyro bias and stopping yaw drift before flight when operating without a yaw sensor. Bigger values allow the detection of a not moving condition with noiser IMU data. Check the XKFM data logged when the vehicle is on ground not moving and adjust the value of OGNM_TEST_SF to be slightly higher than the maximum value of the XKFM.ADR, XKFM.ALR, XKFM.GDR and XKFM.GLR test levels.
Increment |
Range |
---|---|
0.5 |
1.0 to 10.0 |
EK3_GND_EFF_DZ: Baro height ground effect dead zone¶
This parameter sets the size of the dead zone that is applied to negative baro height spikes that can occur when taking off or landing when a vehicle with lift rotors is operating in ground effect ground effect. Set to about 0.5m less than the amount of negative offset in baro height that occurs just prior to takeoff when lift motors are spooling up. Set to 0 if no ground effect is present.
Increment |
Range |
---|---|
0.5 |
0.0 to 10.0 |
EK3_PRIMARY: Primary core number¶
The core number (index in IMU mask) that will be used as the primary EKF core on startup. While disarmed the EKF will force the use of this core. A value of 0 corresponds to the first IMU in EK3_IMU_MASK.
Increment |
Range |
---|---|
1 |
0 to 2 |
EK3_LOG_LEVEL: Logging Level¶
Determines how verbose the EKF3 streaming logging is. A value of 0 provides full logging(default), a value of 1 only XKF4 scaled innovations are logged, a value of 2 both XKF4 and GSF are logged, and a value of 3 disables all streaming logging of EKF3.
Increment |
Range |
---|---|
1 |
0 to 3 |
EK3_GPS_VACC_MAX: GPS vertical accuracy threshold¶
Vertical accuracy threshold for GPS as the altitude source. The GPS will not be used as an altitude source if the reported vertical accuracy of the GPS is larger than this threshold, falling back to baro instead. Set to zero to deactivate the threshold check.
Increment |
Range |
Units |
---|---|---|
0.1 |
0.0 to 10.0 |
meters |
EK3_SRC Parameters¶
EK3_SRC1_POSXY: Position Horizontal Source (Primary)¶
Position Horizontal Source (Primary)
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
EK3_SRC1_VELXY: Velocity Horizontal Source¶
Velocity Horizontal Source
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_SRC1_POSZ: Position Vertical Source¶
Position Vertical Source
Values |
||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
EK3_SRC1_VELZ: Velocity Vertical Source¶
Velocity Vertical Source
Values |
||||||||||
---|---|---|---|---|---|---|---|---|---|---|
|