This is a complete list of the parameters which can be set (e.g. via the MAVLink protocol) to control vehicle behaviour. They are stored in persistent storage on the vehicle.
This list is automatically generated from the latest ardupilot source code, and so may contain parameters which are not yet in the stable released versions of the code.
Rover Parameters
LOG_BITMASK: Log bitmask
Note: This parameter is for advanced users
Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all log types by setting this to 65535. The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Rangefinder=16384, Arming=32768, FullLogs=65535
Bitmask |
Values |
Bit |
Meaning |
0 |
ATTITUDE_FAST |
1 |
ATTITUDE_MED |
2 |
GPS |
3 |
PM |
4 |
THR |
5 |
NTUN |
7 |
IMU |
8 |
CMD |
9 |
CURRENT |
10 |
RANGEFINDER |
11 |
COMPASS |
12 |
CAMERA |
13 |
STEERING |
14 |
RC |
15 |
ARM/DISARM |
19 |
IMU_RAW |
|
Value |
Meaning |
0 |
Disabled |
65535 |
Default |
|
RST_SWITCH_CH: Reset Switch Channel
Note: This parameter is for advanced users
RC channel to use to reset to last flight mode after geofence takeover.
INITIAL_MODE: Initial driving mode
Note: This parameter is for advanced users
This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
SYSID_THISMAV: MAVLink system ID of this vehicle
Note: This parameter is for advanced users
Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
SYSID_MYGCS: MAVLink ground station ID
Note: This parameter is for advanced users
The identifier of the ground station in the MAVLink protocol. Don’t change this unless you also modify the ground station to match.
TELEM_DELAY: Telemetry startup delay
The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
Increment |
Range |
Units |
1 |
0 - 30 |
seconds |
GCS_PID_MASK: GCS PID tuning mask
Note: This parameter is for advanced users
bitmask of PIDs to send MAVLink PID_TUNING messages for
Bitmask |
Values |
Bit |
Meaning |
0 |
Steering |
1 |
Throttle |
2 |
Pitch |
3 |
Left Wheel |
4 |
Right Wheel |
5 |
Sailboat Heel |
|
Value |
Meaning |
0 |
None |
1 |
Steering |
2 |
Throttle |
4 |
Pitch |
8 |
Left Wheel |
16 |
Right Wheel |
32 |
Sailboat Heel |
|
AUTO_TRIGGER_PIN: Auto mode trigger pin
pin number to use to enable the throttle in auto mode. If set to -1 then don’t use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a ‘press button to start’ rover with no receiver.
Values |
Value |
Meaning |
-1 |
Disabled |
0 |
APM TriggerPin0 |
1 |
APM TriggerPin1 |
2 |
APM TriggerPin2 |
3 |
APM TriggerPin3 |
4 |
APM TriggerPin4 |
5 |
APM TriggerPin5 |
6 |
APM TriggerPin6 |
7 |
APM TriggerPin7 |
8 |
APM TriggerPin8 |
50 |
Pixhawk TriggerPin50 |
51 |
Pixhawk TriggerPin51 |
52 |
Pixhawk TriggerPin52 |
53 |
Pixhawk TriggerPin53 |
54 |
Pixhawk TriggerPin54 |
55 |
Pixhawk TriggerPin55 |
|
AUTO_KICKSTART: Auto mode trigger kickstart acceleration
X acceleration in meters/second/second to use to trigger the motor start in auto mode. If set to zero then auto throttle starts immediately when the mode switch happens, otherwise the rover waits for the X acceleration to go above this value before it will start the motor
Increment |
Range |
Units |
0.1 |
0 - 20 |
meters per square second |
CRUISE_SPEED: Target cruise speed in auto modes
The target speed in auto missions.
Increment |
Range |
Units |
0.1 |
0 - 100 |
meters per second |
CRUISE_THROTTLE: Base throttle percentage in auto
The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.
Increment |
Range |
Units |
1 |
0 - 100 |
percent |
FS_ACTION: Failsafe Action
What to do on a failsafe event
Values |
Value |
Meaning |
0 |
Nothing |
1 |
RTL |
2 |
Hold |
3 |
SmartRTL or RTL |
4 |
SmartRTL or Hold |
|
FS_TIMEOUT: Failsafe timeout
The time in seconds that a failsafe condition must persist before the failsafe action is triggered
Increment |
Range |
Units |
0.5 |
1 - 100 |
seconds |
FS_THR_ENABLE: Throttle Failsafe Enable
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range. Failsafe will be triggered when the throttle channel goes below the FS_THR_VALUE for FS_TIMEOUT seconds.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Enabled Continue with Mission in Auto |
|
FS_THR_VALUE: Throttle Failsafe Value
The PWM level on the throttle channel below which throttle failsafe triggers.
Increment |
Range |
1 |
910 - 1100 |
FS_GCS_ENABLE: GCS failsafe enable
Enable ground control station telemetry failsafe. When enabled the Rover will execute the FS_ACTION when it fails to receive MAVLink heartbeat packets for FS_TIMEOUT seconds.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Enabled Continue with Mission in Auto |
|
FS_CRASH_CHECK: Crash check action
What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Hold |
2 |
HoldAndDisarm |
|
FS_EKF_ACTION: EKF Failsafe Action
Note: This parameter is for advanced users
Controls the action that will be taken when an EKF failsafe is invoked
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Hold |
2 |
ReportOnly |
|
FS_EKF_THRESH: EKF failsafe variance threshold
Note: This parameter is for advanced users
Allows setting the maximum acceptable compass and velocity variance
Values |
0.6:Strict,0.8:Default,1.0:Relaxed |
MODE_CH: Mode channel
Note: This parameter is for advanced users
RC Channel to use for driving mode control
MODE1: Mode1
Driving mode for switch position 1 (910 to 1230 and above 2049)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE2: Mode2
Driving mode for switch position 2 (1231 to 1360)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE3: Mode3
Driving mode for switch position 3 (1361 to 1490)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE4: Mode4
Driving mode for switch position 4 (1491 to 1620)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE5: Mode5
Driving mode for switch position 5 (1621 to 1749)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
MODE6: Mode6
Driving mode for switch position 6 (1750 to 2049)
Values |
Value |
Meaning |
0 |
Manual |
1 |
Acro |
3 |
Steering |
4 |
Hold |
5 |
Loiter |
6 |
Follow |
7 |
Simple |
10 |
Auto |
11 |
RTL |
12 |
SmartRTL |
15 |
Guided |
|
TURN_MAX_G: Turning maximum G force
The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
Increment |
Range |
Units |
0.01 |
0.1 - 10 |
standard acceleration due to gravity |
SYSID_ENFORCE: GCS sysid enforcement
Note: This parameter is for advanced users
This controls whether packets from other than the expected GCS system ID will be accepted
Values |
Value |
Meaning |
0 |
NotEnforced |
1 |
Enforced |
|
TURN_RADIUS: Turn radius of vehicle
Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
Increment |
Range |
Units |
0.1 |
0 - 10 |
meters |
ACRO_TURN_RATE: Acro mode turn rate maximum
Acro mode turn rate maximum
Increment |
Range |
Units |
1 |
0 - 360 |
degrees per second |
RTL_SPEED: Return-to-Launch speed default
Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
Increment |
Range |
Units |
0.1 |
0 - 100 |
meters per second |
FRAME_CLASS: Frame Class
Frame Class
Values |
Value |
Meaning |
0 |
Undefined |
1 |
Rover |
2 |
Boat |
3 |
BalanceBot |
|
BAL_PITCH_MAX: BalanceBot Maximum Pitch
Pitch angle in degrees at 100% throttle
Increment |
Range |
Units |
0.1 |
0 - 5 |
degrees |
CRASH_ANGLE: Crash Angle
Pitch/Roll angle limit in degrees for crash check. Zero disables check
Increment |
Range |
Units |
1 |
0 - 60 |
degrees |
FRAME_TYPE: Frame Type
Frame Type
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Undefined |
1 |
Omni3 |
2 |
OmniX |
3 |
OmniPlus |
|
LOIT_TYPE: Loiter type
Loiter behaviour when moving to the target point
Values |
Value |
Meaning |
0 |
Forward or reverse to target point |
1 |
Always face bow towards target point |
2 |
Always face stern towards target point |
|
SIMPLE_TYPE: Simple_Type
Simple mode types
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
InitialHeading |
1 |
CardinalDirections |
|
LOIT_RADIUS: Loiter radius
Vehicle will drift when within this distance of the target position
Increment |
Range |
Units |
1 |
0 - 20 |
meters |
MIS_DONE_BEHAVE: Mission done behave
Behaviour after mission completes
Values |
Value |
Meaning |
0 |
Hold |
1 |
Loiter |
2 |
Acro |
3 |
Manual |
|
BAL_PITCH_TRIM: Balance Bot pitch trim angle
Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
Increment |
Range |
Units |
0.1 |
-2 - 2 |
degrees |
STICK_MIXING: Stick Mixing
Note: This parameter is for advanced users
When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
SPEED_MAX: Speed maximum
Note: This parameter is for advanced users
Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.
Increment |
Range |
Units |
0.1 |
0 - 30 |
meters per second |
LOIT_SPEED_GAIN: Loiter speed gain
Note: This parameter is for advanced users
Determines how agressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.
Increment |
Range |
0.01 |
0 - 5 |
FS_OPTIONS: Rover Failsafe Options
Note: This parameter is for advanced users
Bitmask to enable Rover failsafe options
Bitmask |
Values |
Bit |
Meaning |
0 |
Failsafe enabled in Hold mode |
|
Value |
Meaning |
0 |
None |
1 |
Failsafe enabled in Hold mode |
|
CH7_OPTION: Channel 7 option
What to do use channel 7 for
Values |
Value |
Meaning |
0 |
Nothing |
1 |
SaveWaypoint |
2 |
LearnCruiseSpeed |
3 |
ArmDisarm |
4 |
Manual |
5 |
Acro |
6 |
Steering |
7 |
Hold |
8 |
Auto |
9 |
RTL |
10 |
SmartRTL |
11 |
Guided |
12 |
Loiter |
|
AUX_CH: Auxiliary switch channel
Note: This parameter is for advanced users
RC Channel to use for auxiliary functions including saving waypoints
PIVOT_TURN_ANGLE: Pivot turn angle
Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.
Increment |
Range |
Units |
1 |
0 - 360 |
degrees |
PIVOT_TURN_RATE: Pivot turn rate
Desired pivot turn rate in deg/s.
Increment |
Range |
Units |
1 |
0 - 360 |
degrees per second |
AFS_ Parameters
AFS_ENABLE: Enable Advanced Failsafe
Note: This parameter is for advanced users
This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
AFS_MAN_PIN: Manual Pin
Note: This parameter is for advanced users
This sets a digital output pin to set high when in manual mode
AFS_HB_PIN: Heartbeat Pin
Note: This parameter is for advanced users
This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination.
Values |
Value |
Meaning |
-1 |
Disabled |
49 |
BB Blue GP0 pin 4 |
50 |
AUXOUT1 |
51 |
AUXOUT2 |
52 |
AUXOUT3 |
53 |
AUXOUT4 |
54 |
AUXOUT5 |
55 |
AUXOUT6 |
57 |
BB Blue GP0 pin 3 |
113 |
BB Blue GP0 pin 6 |
116 |
BB Blue GP0 pin 5 |
|
AFS_WP_COMMS: Comms Waypoint
Note: This parameter is for advanced users
Waypoint number to navigate to on comms loss
AFS_WP_GPS_LOSS: GPS Loss Waypoint
Note: This parameter is for advanced users
Waypoint number to navigate to on GPS lock loss
AFS_TERMINATE: Force Terminate
Note: This parameter is for advanced users
Can be set in flight to force termination of the heartbeat signal
AFS_TERM_ACTION: Terminate action
Note: This parameter is for advanced users
This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter
AFS_TERM_PIN: Terminate Pin
Note: This parameter is for advanced users
This sets a digital output pin to set high on flight termination
Values |
Value |
Meaning |
-1 |
Disabled |
49 |
BB Blue GP0 pin 4 |
50 |
AUXOUT1 |
51 |
AUXOUT2 |
52 |
AUXOUT3 |
53 |
AUXOUT4 |
54 |
AUXOUT5 |
55 |
AUXOUT6 |
57 |
BB Blue GP0 pin 3 |
113 |
BB Blue GP0 pin 6 |
116 |
BB Blue GP0 pin 5 |
|
AFS_AMSL_LIMIT: AMSL limit
Note: This parameter is for advanced users
This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
AFS_AMSL_ERR_GPS: Error margin for GPS based AMSL limit
Note: This parameter is for advanced users
This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
AFS_QNH_PRESSURE: QNH pressure
Note: This parameter is for advanced users
This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
AFS_MAX_GPS_LOSS: Maximum number of GPS loss events
Note: This parameter is for advanced users
Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
AFS_GEOFENCE: Enable geofence Advanced Failsafe
Note: This parameter is for advanced users
This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC: Enable RC Advanced Failsafe
Note: This parameter is for advanced users
This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
AFS_RC_MAN_ONLY: Enable RC Termination only in manual control modes
Note: This parameter is for advanced users
If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
AFS_DUAL_LOSS: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
Note: This parameter is for advanced users
This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a “dual loss” and cause termination.
AFS_RC_FAIL_TIME: RC failure time
Note: This parameter is for advanced users
This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
AFS_MAX_RANGE: Max allowed range
Note: This parameter is for advanced users
This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
ARSPD Parameters
ARSPD_TYPE: Airspeed type
Type of airspeed sensor
Values |
Value |
Meaning |
0 |
None |
1 |
I2C-MS4525D0 |
2 |
Analog |
3 |
I2C-MS5525 |
4 |
I2C-MS5525 (0x76) |
5 |
I2C-MS5525 (0x77) |
6 |
I2C-SDP3X |
7 |
I2C-DLVR-5in |
8 |
UAVCAN |
9 |
I2C-DLVR-10in |
10 |
I2C-DLVR-20in |
11 |
I2C-DLVR-30in |
12 |
I2C-DLVR-60in |
13 |
NMEA water speed |
14 |
MSP |
15 |
ASP5033 |
|
ARSPD_USE: Airspeed use
Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).
Values |
Value |
Meaning |
0 |
DoNotUse |
1 |
Use |
2 |
UseWhenZeroThrottle |
|
ARSPD_OFFSET: Airspeed offset
Note: This parameter is for advanced users
Airspeed calibration offset
ARSPD_RATIO: Airspeed ratio
Note: This parameter is for advanced users
Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.
ARSPD_PIN: Airspeed pin
Note: This parameter is for advanced users
The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
ARSPD_AUTOCAL: Automatic airspeed ratio calibration
Note: This parameter is for advanced users
Enables automatic adjustment of ARSPD_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_ORDER: Control pitot tube order
Note: This parameter is for advanced users
Changes the pitot tube order to specify the dynamic pressure side of the sensor. Accepts either if set to 2. Accepts only one side if set to 0 or 1 and can help detect excessive pressure on the static port without indicating positive airspeed.
ARSPD_SKIP_CAL: Skip airspeed calibration on startup
Note: This parameter is for advanced users
This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ARSPD_PSI_RANGE: The PSI range of the device
Note: This parameter is for advanced users
This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
ARSPD_BUS: Airspeed I2C bus
Note: This parameter is for advanced users
Bus number of the I2C bus where the airspeed sensor is connected
Values |
Value |
Meaning |
0 |
Bus0(internal) |
1 |
Bus1(external) |
2 |
Bus2(auxillary) |
|
ARSPD_PRIMARY: Primary airspeed sensor
Note: This parameter is for advanced users
This selects which airspeed sensor will be the primary if multiple sensors are found
Values |
Value |
Meaning |
0 |
FirstSensor |
1 |
2ndSensor |
|
ARSPD_OPTIONS: Airspeed options bitmask
Note: This parameter is for advanced users
Bitmask of options to use with airspeed. Disable and/or re-enable sensor based on the difference between airspeed and ground speed based on ARSPD_WIND_MAX threshold, if set
Bitmask |
Bit |
Meaning |
0 |
Disable sensor |
1 |
Re-enable sensor |
|
ARSPD_WIND_MAX: Maximum airspeed and ground speed difference
Note: This parameter is for advanced users
If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTION this health value can be used to disable the sensor.
ARSPD_WIND_WARN: Airspeed and ground speed difference that gives a warning
Note: This parameter is for advanced users
If the difference between airspeed and ground speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used.
ARSPD2_TYPE: Second Airspeed type
Type of 2nd airspeed sensor
Values |
Value |
Meaning |
0 |
None |
1 |
I2C-MS4525D0 |
2 |
Analog |
3 |
I2C-MS5525 |
4 |
I2C-MS5525 (0x76) |
5 |
I2C-MS5525 (0x77) |
6 |
I2C-SDP3X |
7 |
I2C-DLVR-5in |
8 |
UAVCAN |
9 |
I2C-DLVR-10in |
10 |
I2C-DLVR-20in |
11 |
I2C-DLVR-30in |
12 |
I2C-DLVR-60in |
13 |
NMEA water speed |
14 |
MSP |
15 |
ASP5033 |
|
ARSPD2_USE: Enable use of 2nd airspeed sensor
use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won’t be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
Values |
Value |
Meaning |
0 |
Don’t Use |
1 |
use |
2 |
UseWhenZeroThrottle |
|
ARSPD2_OFFSET: Airspeed offset for 2nd airspeed sensor
Note: This parameter is for advanced users
Airspeed calibration offset
ARSPD2_RATIO: Airspeed ratio for 2nd airspeed sensor
Note: This parameter is for advanced users
Airspeed calibration ratio
ARSPD2_PIN: Airspeed pin for 2nd airspeed sensor
Note: This parameter is for advanced users
Pin number indicating location of analog airspeed sensors. Pixhawk/Cube if set to 15.
ARSPD2_AUTOCAL: Automatic airspeed ratio calibration for 2nd airspeed sensor
Note: This parameter is for advanced users
If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
ARSPD2_TUBE_ORDR: Control pitot tube order of 2nd airspeed sensor
Note: This parameter is for advanced users
This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic 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 it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed.
ARSPD2_SKIP_CAL: Skip airspeed calibration on startup for 2nd sensor
Note: This parameter is for advanced users
This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ARSPD2_PSI_RANGE: The PSI range of the device for 2nd sensor
Note: This parameter is for advanced users
This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
ARSPD2_BUS: Airspeed I2C bus for 2nd sensor
Note: This parameter is for advanced users
The bus number of the I2C bus to look for the sensor on
Values |
Value |
Meaning |
0 |
Bus0(internal) |
1 |
Bus1(external) |
2 |
Bus2(auxillary) |
|
ATC Parameters
ATC_STR_RAT_P: Steering control rate P gain
Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
Increment |
Range |
0.001 |
0.000 - 2.000 |
ATC_STR_RAT_I: Steering control I gain
Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
Increment |
Range |
0.001 |
0.000 - 2.000 |
ATC_STR_RAT_IMAX: Steering control I gain maximum
Steering control I gain maximum. Constrains the steering output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_STR_RAT_D: Steering control D gain
Steering control D gain. Compensates for short-term change in desired turn rate vs actual
Increment |
Range |
0.001 |
0.000 - 0.400 |
ATC_STR_RAT_FF: Steering control feed forward
Steering control feed forward
Increment |
Range |
0.001 |
0.000 - 3.000 |
ATC_STR_RAT_FILT: Steering control filter frequency
Steering control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTT: Steering control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTE: Steering control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_FLTD: Steering control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_STR_RAT_SMAX: Steering slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_SPEED_P: Speed control P gain
Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.010 - 2.000 |
ATC_SPEED_I: Speed control I gain
Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SPEED_IMAX: Speed control I gain maximum
Speed control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_SPEED_D: Speed control D gain
Speed control D gain. Compensates for short-term change in desired speed vs actual
Increment |
Range |
0.001 |
0.000 - 0.400 |
ATC_SPEED_FF: Speed control feed forward
Speed control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_SPEED_FILT: Speed control filter frequency
Speed control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTT: Speed control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTE: Speed control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_FLTD: Speed control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SPEED_SMAX: Speed control slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_ACCEL_MAX: Speed control acceleration (and deceleration) maximum in m/s/s
Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
Increment |
Range |
Units |
0.1 |
0.0 - 10.0 |
meters per square second |
ATC_BRAKE: Speed control brake enable/disable
Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
Values |
Value |
Meaning |
0 |
Disable |
1 |
Enable |
|
ATC_STOP_SPEED: Speed control stop speed
Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
Increment |
Range |
Units |
0.01 |
0.00 - 0.50 |
meters per second |
ATC_STR_ANG_P: Steering control angle P gain
Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
Increment |
Range |
0.1 |
1.000 - 10.000 |
ATC_STR_ACC_MAX: Steering control angular acceleration maximum
Steering control angular acceleration maximum (in deg/s/s). 0 to disable acceleration limiting
Increment |
Range |
Units |
0.1 |
0 - 1000 |
degrees per square second |
ATC_STR_RAT_MAX: Steering control rotation rate maximum
Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
Increment |
Range |
Units |
0.1 |
0 - 1000 |
degrees per second |
ATC_DECEL_MAX: Speed control deceleration maximum in m/s/s
Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
Increment |
Range |
Units |
0.1 |
0.0 - 10.0 |
meters per square second |
ATC_BAL_P: Pitch control P gain
Pitch control P gain for BalanceBots. Converts the error between the desired pitch (in radians) and actual pitch to a motor output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_BAL_I: Pitch control I gain
Pitch control I gain for BalanceBots. Corrects long term error between the desired pitch (in radians) and actual pitch
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_BAL_IMAX: Pitch control I gain maximum
Pitch control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_BAL_D: Pitch control D gain
Pitch control D gain. Compensates for short-term change in desired pitch vs actual
Increment |
Range |
0.001 |
0.000 - 0.100 |
ATC_BAL_FF: Pitch control feed forward
Pitch control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_BAL_FILT: Pitch control filter frequency
Pitch control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTT: Pitch control Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTE: Pitch control Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_FLTD: Pitch control Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_BAL_SMAX: Pitch control slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
ATC_BAL_SPD_FF: Pitch control feed forward from speed
Pitch control feed forward from speed
Increment |
Range |
0.01 |
0.0 - 10.0 |
ATC_SAIL_P: Sail Heel control P gain
Sail Heel control P gain for sailboats. Converts the error between the desired heel angle (in radians) and actual heel to a main sail output (in the range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SAIL_I: Sail Heel control I gain
Sail Heel control I gain for sailboats. Corrects long term error between the desired heel angle (in radians) and actual
Increment |
Range |
0.01 |
0.000 - 2.000 |
ATC_SAIL_IMAX: Sail Heel control I gain maximum
Sail Heel control I gain maximum. Constrains the maximum I term contribution to the main sail output (range -1 to +1)
Increment |
Range |
0.01 |
0.000 - 1.000 |
ATC_SAIL_D: Sail Heel control D gain
Sail Heel control D gain. Compensates for short-term change in desired heel angle vs actual
Increment |
Range |
0.001 |
0.000 - 0.100 |
ATC_SAIL_FF: Sail Heel control feed forward
Sail Heel control feed forward
Increment |
Range |
0.001 |
0.000 - 0.500 |
ATC_SAIL_FILT: Sail Heel control filter frequency
Sail Heel control input filter. Lower values reduce noise but add delay.
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTT: Sail Heel Target filter frequency in Hz
Target filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTE: Sail Heel Error filter frequency in Hz
Error filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_FLTD: Sail Heel Derivative term filter frequency in Hz
Derivative filter frequency in Hz
Increment |
Range |
Units |
0.1 |
0.000 - 100.000 |
hertz |
ATC_SAIL_SMAX: Sail heel slew rate limit
Note: This parameter is for advanced users
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Increment |
Range |
0.5 |
0 - 200 |
BRD_ Parameters
BRD_PWM_COUNT: Auxiliary pin config
Note: This parameter is for advanced users
Controls number of FMU outputs which are setup for PWM. All unassigned pins can be used for GPIO
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
No PWMs |
1 |
One PWMs |
2 |
Two PWMs |
3 |
Three PWMs |
4 |
Four PWMs |
5 |
Five PWMs |
6 |
Six PWMs |
7 |
Seven PWMs |
8 |
Eight PWMs |
|
BRD_SER1_RTSCTS: Serial 1 flow control
Note: This parameter is for advanced users
Enable flow control on serial 1 (telemetry 1) on Pixhawk. 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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER2_RTSCTS: Serial 2 flow control
Note: This parameter is for advanced users
Enable flow control on serial 2 (telemetry 2) on Pixhawk and STATE. 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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER3_RTSCTS: Serial 3 flow control
Note: This parameter is for advanced users
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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER4_RTSCTS: Serial 4 flow control
Note: This parameter is for advanced users
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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SER5_RTSCTS: Serial 5 flow control
Note: This parameter is for advanced users
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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
2 |
Auto |
|
BRD_SAFETYENABLE: Enable use of safety arming 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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_SBUS_OUT: SBUS output rate
Note: This parameter is for advanced users
This sets the SBUS output frame rate in Hz
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
50Hz |
2 |
75Hz |
3 |
100Hz |
4 |
150Hz |
5 |
200Hz |
6 |
250Hz |
7 |
300Hz |
|
BRD_SERIAL_NUM: User-defined serial number
User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
BRD_SAFETY_MASK: Outputs which ignore the safety switch state
Note: This parameter is for advanced users
A bitmask which controls what outputs can move while the safety switch has not been pressed
Bitmask |
RebootRequired |
Values |
Bit |
Meaning |
0 |
Output1 |
1 |
Output2 |
2 |
Output3 |
3 |
Output4 |
4 |
Output5 |
5 |
Output6 |
6 |
Output7 |
7 |
Output8 |
8 |
Output9 |
9 |
Output10 |
10 |
Output11 |
11 |
Output12 |
12 |
Output13 |
13 |
Output14 |
|
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_IMU_TARGTEMP: Target IMU temperature
Note: This parameter is for advanced users
This sets the target IMU temperature for boards with controllable IMU heating units. DO NOT SET -1 on The Cube. A value of -1 sets PH1 behaviour
Range |
Units |
-1 - 80 |
degrees Celsius |
BRD_TYPE: Board type
Note: This parameter is for advanced users
This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
AUTO |
1 |
PX4V1 |
2 |
Pixhawk |
3 |
Cube/Pixhawk2 |
4 |
Pixracer |
5 |
PixhawkMini |
6 |
Pixhawk2Slim |
13 |
Intel Aero FC |
14 |
Pixhawk Pro |
20 |
AUAV2.1 |
21 |
PCNC1 |
22 |
MINDPXV2 |
23 |
SP01 |
24 |
CUAVv5/FMUV5 |
30 |
VRX BRAIN51 |
32 |
VRX BRAIN52 |
33 |
VRX BRAIN52E |
34 |
VRX UBRAIN51 |
35 |
VRX UBRAIN52 |
36 |
VRX CORE10 |
38 |
VRX BRAIN54 |
39 |
PX4 FMUV6 |
100 |
PX4 OLDDRIVERS |
|
BRD_IO_ENABLE: Enable IO co-processor
Note: This parameter is for advanced users
This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
BRD_VBUS_MIN: Autopilot board voltage requirement
Note: This parameter is for advanced users
Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
0.1 |
4.0 - 5.5 |
volt |
BRD_VSERVO_MIN: Servo voltage requirement
Note: This parameter is for advanced users
Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
Increment |
Range |
Units |
0.1 |
3.3 - 12.0 |
volt |
BRD_SD_SLOWDOWN: microSD slowdown
Note: This parameter is for advanced users
This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
BRD_PWM_VOLT_SEL: Set PWM Out Voltage
Note: This parameter is for advanced users
This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output.
Values |
Value |
Meaning |
0 |
3.3V |
1 |
5V |
|
BRD_OPTIONS: Board options
Note: This parameter is for advanced users
Board specific option flags
Bitmask |
Bit |
Meaning |
0 |
Enable hardware watchdog |
1 |
Disable MAVftp |
2 |
Enable set of internal parameters |
|
BRD_BOOT_DELAY: Boot delay
Note: This parameter is for advanced users
This adds a delay in milliseconds to boot to ensure peripherals initialise fully
Range |
Units |
0 - 10000 |
milliseconds |
BRD_IMUHEAT_P: IMU Heater P gain
Note: This parameter is for advanced users
IMU Heater P gain
Increment |
Range |
1 |
1 - 500 |
BRD_IMUHEAT_I: IMU Heater I gain
Note: This parameter is for advanced users
IMU Heater integrator gain
Increment |
Range |
0.1 |
0 - 1 |
BRD_IMUHEAT_IMAX: IMU Heater IMAX
Note: This parameter is for advanced users
IMU Heater integrator maximum
Increment |
Range |
1 |
0 - 100 |
BRD_ALT_CONFIG: Alternative HW config
Note: This parameter is for advanced users
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 |
RebootRequired |
1 |
0 - 10 |
True |
COMPASS_ Parameters
COMPASS_OFS_X: Compass offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to the compass x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS_Y: Compass offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to the compass y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS_Z: Compass offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to the compass z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
1 |
-400 - 400 |
milligauss |
COMPASS_DEC: Compass declination
An angle to compensate between the true north and magnetic north
Increment |
Range |
Units |
0.01 |
-3.142 - 3.142 |
radians |
COMPASS_LEARN: Learn compass offsets automatically
Note: This parameter is for advanced users
Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Internal-Learning |
2 |
EKF-Learning |
3 |
InFlight-Learning |
|
COMPASS_USE: Use compass for yaw
Note: This parameter is for advanced users
Enable or disable the use of the compass (instead of the GPS) for determining heading
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_AUTODEC: Auto Declination
Note: This parameter is for advanced users
Enable or disable the automatic calculation of the declination based on gps location
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_MOTCT: Motor interference compensation type
Note: This parameter is for advanced users
Set motor interference compensation type to disabled, throttle or current. Do not change manually.
Calibration |
Values |
1 |
Value |
Meaning |
0 |
Disabled |
1 |
Use Throttle |
2 |
Use Current |
|
COMPASS_MOT_X: Motor interference compensation for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT_Y: Motor interference compensation for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT_Z: Motor interference compensation for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to the compass’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_ORIENT: Compass orientation
Note: This parameter is for advanced users
The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
100 |
Custom |
|
COMPASS_EXTERNAL: Compass is attached via an external cable
Note: This parameter is for advanced users
Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_OFS2_X: Compass2 offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to compass2’s x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS2_Y: Compass2 offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to compass2’s y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS2_Z: Compass2 offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to compass2’s z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
1 |
-400 - 400 |
milligauss |
COMPASS_MOT2_X: Motor interference compensation to compass2 for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT2_Y: Motor interference compensation to compass2 for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT2_Z: Motor interference compensation to compass2 for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass2’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_OFS3_X: Compass3 offsets in milligauss on the X axis
Note: This parameter is for advanced users
Offset to be added to compass3’s x-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS3_Y: Compass3 offsets in milligauss on the Y axis
Note: This parameter is for advanced users
Offset to be added to compass3’s y-axis values to compensate for metal in the frame
Calibration |
Increment |
Range |
Units |
1 |
1 |
-400 - 400 |
milligauss |
COMPASS_OFS3_Z: Compass3 offsets in milligauss on the Z axis
Note: This parameter is for advanced users
Offset to be added to compass3’s z-axis values to compensate for metal in the frame
Increment |
Range |
Units |
1 |
-400 - 400 |
milligauss |
COMPASS_MOT3_X: Motor interference compensation to compass3 for body frame X axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT3_Y: Motor interference compensation to compass3 for body frame Y axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Calibration |
Increment |
Range |
Units |
1 |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_MOT3_Z: Motor interference compensation to compass3 for body frame Z axis
Note: This parameter is for advanced users
Multiplied by the current throttle and added to compass3’s z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Increment |
Range |
Units |
1 |
-1000 - 1000 |
milligauss per ampere |
COMPASS_DEV_ID: Compass device id
Note: This parameter is for advanced users
Compass device id. Automatically detected, do not set manually
COMPASS_DEV_ID2: Compass2 device id
Note: This parameter is for advanced users
Second compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID3: Compass3 device id
Note: This parameter is for advanced users
Third compass’s device id. Automatically detected, do not set manually
COMPASS_USE2: Compass2 used for yaw
Note: This parameter is for advanced users
Enable or disable the secondary compass for determining heading.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_ORIENT2: Compass2 orientation
Note: This parameter is for advanced users
The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
100 |
Custom |
|
COMPASS_EXTERN2: Compass2 is attached via an external cable
Note: This parameter is for advanced users
Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_USE3: Compass3 used for yaw
Note: This parameter is for advanced users
Enable or disable the tertiary compass for determining heading.
Values |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
COMPASS_ORIENT3: Compass3 orientation
Note: This parameter is for advanced users
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.
Values |
Value |
Meaning |
0 |
None |
1 |
Yaw45 |
2 |
Yaw90 |
3 |
Yaw135 |
4 |
Yaw180 |
5 |
Yaw225 |
6 |
Yaw270 |
7 |
Yaw315 |
8 |
Roll180 |
9 |
Roll180Yaw45 |
10 |
Roll180Yaw90 |
11 |
Roll180Yaw135 |
12 |
Pitch180 |
13 |
Roll180Yaw225 |
14 |
Roll180Yaw270 |
15 |
Roll180Yaw315 |
16 |
Roll90 |
17 |
Roll90Yaw45 |
18 |
Roll90Yaw90 |
19 |
Roll90Yaw135 |
20 |
Roll270 |
21 |
Roll270Yaw45 |
22 |
Roll270Yaw90 |
23 |
Roll270Yaw135 |
24 |
Pitch90 |
25 |
Pitch270 |
26 |
Pitch180Yaw90 |
27 |
Pitch180Yaw270 |
28 |
Roll90Pitch90 |
29 |
Roll180Pitch90 |
30 |
Roll270Pitch90 |
31 |
Roll90Pitch180 |
32 |
Roll270Pitch180 |
33 |
Roll90Pitch270 |
34 |
Roll180Pitch270 |
35 |
Roll270Pitch270 |
36 |
Roll90Pitch180Yaw90 |
37 |
Roll90Yaw270 |
38 |
Yaw293Pitch68Roll180 |
39 |
Pitch315 |
40 |
Roll90Pitch315 |
100 |
Custom |
|
COMPASS_EXTERN3: Compass3 is attached via an external cable
Note: This parameter is for advanced users
Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Values |
Value |
Meaning |
0 |
Internal |
1 |
External |
2 |
ForcedExternal |
|
COMPASS_DIA_X: Compass soft-iron diagonal X component
Note: This parameter is for advanced users
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]]
COMPASS_DIA_Y: Compass soft-iron diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_DIA_Z: Compass soft-iron diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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]]
COMPASS_ODI_Y: Compass soft-iron off-diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_ODI_Z: Compass soft-iron off-diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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]]
COMPASS_DIA2_Y: Compass2 soft-iron diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_DIA2_Z: Compass2 soft-iron diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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]]
COMPASS_ODI2_Y: Compass2 soft-iron off-diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_ODI2_Z: Compass2 soft-iron off-diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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]]
COMPASS_DIA3_Y: Compass3 soft-iron diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_DIA3_Z: Compass3 soft-iron diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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]]
COMPASS_ODI3_Y: Compass3 soft-iron off-diagonal Y component
Note: This parameter is for advanced users
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]]
COMPASS_ODI3_Z: Compass3 soft-iron off-diagonal Z component
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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 - 32 |
Value |
Meaning |
4 |
Very Strict |
8 |
Strict |
16 |
Default |
32 |
Relaxed |
|
COMPASS_OFFS_MAX: Compass maximum offset
Note: This parameter is for advanced users
This sets the maximum allowed compass offset in calibration and arming checks
Increment |
Range |
1 |
500 - 3000 |
COMPASS_TYPEMASK: Compass disable driver type mask
Note: This parameter is for advanced users
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 |
Bit |
Meaning |
0 |
HMC5883 |
1 |
LSM303D |
2 |
AK8963 |
3 |
BMM150 |
4 |
LSM9DS1 |
5 |
LIS3MDL |
6 |
AK09916 |
7 |
IST8310 |
8 |
ICM20948 |
9 |
MMC3416 |
11 |
UAVCAN |
12 |
QMC5883 |
14 |
MAG3110 |
15 |
IST8308 |
16 |
RM3100 |
17 |
MSP |
18 |
ExternalAHRS |
|
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 - 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 |
Value |
Meaning |
0 |
Disabled |
1 |
CheckOnly |
2 |
CheckAndFix |
|
COMPASS_PRIO1_ID: Compass device id with 1st order priority
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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
Note: This parameter is for advanced users
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 |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
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
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
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
COMPASS_OPTIONS: Compass options
Note: This parameter is for advanced users
This sets options to change the behaviour of the compass
Bitmask |
Bit |
Meaning |
0 |
CalRequireGPS |
|
COMPASS_DEV_ID4: Compass4 device id
Note: This parameter is for advanced users
Extra 4th compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID5: Compass5 device id
Note: This parameter is for advanced users
Extra 5th compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID6: Compass6 device id
Note: This parameter is for advanced users
Extra 6th compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID7: Compass7 device id
Note: This parameter is for advanced users
Extra 7th compass’s device id. Automatically detected, do not set manually
COMPASS_DEV_ID8: Compass8 device id
Note: This parameter is for advanced users
Extra 8th compass’s device id. Automatically detected, do not set manually
COMPASS_CUS_ROLL: Custom orientation roll offset
Note: This parameter is for advanced users
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 |
RebootRequired |
Units |
1 |
-180 - 180 |
True |
degrees |
COMPASS_CUS_PIT: Custom orientation pitch offset
Note: This parameter is for advanced users
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 |
RebootRequired |
Units |
1 |
-180 - 180 |
True |
degrees |
COMPASS_CUS_YAW: Custom orientation yaw offset
Note: This parameter is for advanced users
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 |
RebootRequired |
Units |
1 |
-180 - 180 |
True |
degrees |
EK2_ Parameters
EK2_ENABLE: Enable EKF2
Note: This parameter is for advanced users
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.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Disabled |
1 |
Enabled |
|
EK2_GPS_TYPE: GPS mode control
Note: This parameter is for advanced users
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 |
Value |
Meaning |
0 |
GPS 3D Vel and 2D Pos |
1 |
GPS 2D vel and 2D pos |
2 |
GPS 2D pos |
3 |
No GPS |
|
EK2_VELNE_M_NSE: GPS horizontal velocity measurement noise (m/s)
Note: This parameter is for advanced users
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 - 5.0 |
meters per second |
EK2_VELD_M_NSE: GPS vertical velocity measurement noise (m/s)
Note: This parameter is for advanced users
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 - 5.0 |
meters per second |
EK2_VEL_I_GATE: GPS velocity innovation gate size
Note: This parameter is for advanced users
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 willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
Increment |
Range |
25 |
100 - 1000 |
EK2_POSNE_M_NSE: GPS horizontal position measurement noise (m)
Note: This parameter is for advanced users
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 - 10.0 |
meters |
EK2_POS_I_GATE: GPS position measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_GLITCH_RAD: GPS glitch radius gate size (m)
Note: This parameter is for advanced users
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 - 100 |
meters |
EK2_ALT_SOURCE: Primary altitude sensor source
Note: This parameter is for advanced users
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).
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
Use Baro |
1 |
Use Range Finder |
2 |
Use GPS |
3 |
Use Range Beacon |
|
EK2_ALT_M_NSE: Altitude measurement noise (m)
Note: This parameter is for advanced users
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 - 10.0 |
meters |
EK2_HGT_I_GATE: Height measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_HGT_DELAY: Height measurement delay (msec)
Note: This parameter is for advanced users
This is the number of msec that the Height measurements lag behind the inertial measurements.
Increment |
Range |
RebootRequired |
Units |
10 |
0 - 250 |
True |
milliseconds |
EK2_MAG_M_NSE: Magnetometer measurement noise (Gauss)
Note: This parameter is for advanced users
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 - 0.5 |
gauss |
EK2_MAG_CAL: Magnetometer default fusion mode
Note: This parameter is for advanced users
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 |
Value |
Meaning |
0 |
When flying |
1 |
When manoeuvring |
2 |
Never |
3 |
After first climb yaw reset |
4 |
Always |
|
EK2_MAG_I_GATE: Magnetometer measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_EAS_M_NSE: Equivalent airspeed measurement noise (m/s)
Note: This parameter is for advanced users
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 - 5.0 |
meters per second |
EK2_EAS_I_GATE: Airspeed measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_RNG_M_NSE: Range finder measurement noise (m)
Note: This parameter is for advanced users
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 - 10.0 |
meters |
EK2_RNG_I_GATE: Range finder measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_MAX_FLOW: Maximum valid optical flow rate
Note: This parameter is for advanced users
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 - 4.0 |
radians per second |
EK2_FLOW_M_NSE: Optical flow measurement noise (rad/s)
Note: This parameter is for advanced users
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 - 1.0 |
radians per second |
EK2_FLOW_I_GATE: Optical Flow measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_FLOW_DELAY: Optical Flow measurement delay (msec)
Note: This parameter is for advanced users
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 |
RebootRequired |
Units |
10 |
0 - 127 |
True |
milliseconds |
EK2_GYRO_P_NSE: Rate gyro noise (rad/s)
Note: This parameter is for advanced users
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 - 0.1 |
radians per second |
EK2_ACC_P_NSE: Accelerometer noise (m/s^2)
Note: This parameter is for advanced users
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 - 1.0 |
meters per square second |
EK2_GBIAS_P_NSE: Rate gyro bias stability (rad/s/s)
Note: This parameter is for advanced users
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 - 0.001 |
radians per square second |
EK2_GSCL_P_NSE: Rate gyro scale factor stability (1/s)
Note: This parameter is for advanced users
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 - 0.001 |
hertz |
EK2_ABIAS_P_NSE: Accelerometer bias stability (m/s^3)
Note: This parameter is for advanced users
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 - 0.005 |
meters per cubic second |
EK2_WIND_P_NSE: Wind velocity process noise (m/s^2)
Note: This parameter is for advanced users
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 - 1.0 |
meters per square second |
EK2_WIND_PSCALE: Height rate to wind process noise scaler
Note: This parameter is for advanced users
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 - 1.0 |
EK2_GPS_CHECK: GPS preflight check
Note: This parameter is for advanced users
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 |
Bit |
Meaning |
0 |
NSats |
1 |
HDoP |
2 |
speed error |
3 |
position error |
4 |
yaw error |
5 |
pos drift |
6 |
vert speed |
7 |
horiz speed |
|
EK2_IMU_MASK: Bitmask of active IMUs
Note: This parameter is for advanced users
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 |
RebootRequired |
Bit |
Meaning |
0 |
FirstIMU |
1 |
SecondIMU |
2 |
ThirdIMU |
3 |
FourthIMU |
4 |
FifthIMU |
5 |
SixthIMU |
|
True |
EK2_CHECK_SCALE: GPS accuracy check scaler (%)
Note: This parameter is for advanced users
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 - 200 |
percent |
EK2_NOAID_M_NSE: Non-GPS operation position uncertainty (m)
Note: This parameter is for advanced users
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 - 50.0 |
meters |
EK2_YAW_M_NSE: Yaw measurement noise (rad)
Note: This parameter is for advanced users
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 - 1.0 |
radians |
EK2_YAW_I_GATE: Yaw measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_TAU_OUTPUT: Output complementary filter time constant (centi-sec)
Note: This parameter is for advanced users
Sets the time constant of the output complementary filter/predictor in centi-seconds.
Increment |
Range |
Units |
5 |
10 - 50 |
centiseconds |
EK2_MAGE_P_NSE: Earth magnetic field process noise (gauss/s)
Note: This parameter is for advanced users
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 - 0.01 |
gauss per second |
EK2_MAGB_P_NSE: Body magnetic field process noise (gauss/s)
Note: This parameter is for advanced users
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 - 0.01 |
gauss per second |
EK2_RNG_USE_HGT: Range finder switch height percentage
Note: This parameter is for advanced users
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 - 70 |
percent |
EK2_TERR_GRAD: Maximum terrain gradient
Note: This parameter is for advanced users
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 - 0.2 |
EK2_BCN_M_NSE: Range beacon measurement noise (m)
Note: This parameter is for advanced users
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 - 10.0 |
meters |
EK2_BCN_I_GTE: Range beacon measurement gate size
Note: This parameter is for advanced users
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 - 1000 |
EK2_BCN_DELAY: Range beacon measurement delay (msec)
Note: This parameter is for advanced users
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 |
RebootRequired |
Units |
10 |
0 - 127 |
True |
milliseconds |
EK2_RNG_USE_SPD: Range finder max ground speed
Note: This parameter is for advanced users
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 - 6.0 |
meters per second |
EK2_MAG_MASK: Bitmask of active EKF cores that will always use heading fusion
Note: This parameter is for advanced users
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 |
RebootRequired |
Bit |
Meaning |
0 |
FirstEKF |
1 |
SecondEKF |
2 |
ThirdEKF |
3 |
FourthEKF |
4 |
FifthEKF |
5 |
SixthEKF |
|
True |
EK2_OGN_HGT_MASK: Bitmask control of EKF reference height correction
Note: This parameter is for advanced users
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 |
RebootRequired |
Bit |
Meaning |
0 |
Correct when using Baro height |
1 |
Correct when using range finder height |
2 |
Apply corrections to local position |
|
True |
EK2_FLOW_USE: Optical flow use bitmask
Note: This parameter is for advanced users
Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
RebootRequired |
Values |
True |
Value |
Meaning |
0 |
None |
1 |
Navigation |
2 |
Terrain |
|
EK2_MAG_EF_LIM: EarthField error limit
Note: This parameter is for advanced users
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 - 500 |
milligauss |