Command Line Interface (CLI)

Cleanflight has a command line interface (CLI) that can be used to change settings and configure the FC.

Accessing the CLI.

The CLI can be accessed via the GUI tool or via a terminal emulator connected to the CLI serial port.

  1. Connect your terminal emulator to the CLI serial port (which, by default, is the same as the MSP serial port)
  2. Use the baudrate specified by msp_baudrate (115200 by default).
  3. Send a # character.

To save your settings type in ‘save’, saving will reboot the flight controller.

To exit the CLI without saving power off the flight controller or type in 'exit’.

To see a list of other commands type in 'help’ and press return.

To dump your configuration (including the current profile), use the 'dump’ command.

See the other documentation sections for details of the cli commands and settings that are available.

Backup via CLI

Disconnect main power, connect to cli via USB/FTDI.

dump using cli

rateprofile 0
profile 0
dump

dump profiles using cli if you use them

profile 1
dump profile
profile 2
dump profile

dump rate profiles using cli if you use them

rateprofile 1
dump rates
rateprofile 2
dump rates

copy screen output to a file and save it.

Restore via CLI.

Use the cli defaults command first.

When restoring from a backup it is a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created youwill be able to see the cli changes between firmware versions. For instance, in December 2014 the default GPS navigation PIDs changed. If you blindly restore your backup you would not benefit from these new defaults.

Use the CLI and send all the output from the saved backup commands.

Do not send the file too fast, if you do the FC might not be able to keep up when using USART adapters (including built in ones) since there is no hardware serial flow control.

You may find you have to copy/paste a few lines at a time.

Repeat the backup process again!

Compare the two backups to make sure you are happy with your restored settings.

Re-apply any new defaults as desired.

CLI Command Reference

Click on a command to jump to the relevant documentation page.

Command Description
1wire <esc> passthrough 1wire to the specified esc
adjrange show/set adjustment ranges settings
aux show/set aux settings
mmix design custom motor mixer
smix design custom servo mixer
color configure colors
defaults reset to defaults and reboot
dump print configurable settings in a pastable form
exit
feature list or -val or val
get get variable value
gpspassthrough passthrough gps to serial
help
led configure leds
map mapping of rc channel order
mixer mixer name or list
mode_color configure mode colors
motor get/set motor output value
play_sound index, or none for next
profile index (0 to 2)
rateprofile index (0 to 2)
rxrange configure rx channel ranges (end-points)
rxfail show/set rx failsafe settings
save save and reboot
set name=value or blank or * for list
status show system status
version show version
serial configure serial ports
servo configure servos
sd_info sdcard info
tasks show task stats

CLI Variable Reference

Click on a variable to jump to the relevant documentation page.

Variable Description/Units Min Max Default Type Datatype
looptime This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). Default of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. 0 9000 3500 Master UINT16
emf_avoidance Default value is OFF for 72MHz processor speed. Setting this to ON increases the processor speed, to move the 6th harmonic away from 432MHz. OFF ON OFF Master UINT8
i2c_highspeed Enabling this feature speeds up IMU speed significantly and faster looptimes are possible. OFF ON ON Master UINT8
gyro_sync This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Use gyro_lpf and gyro_sync_denom determine the gyro refresh rate. Note that different targets have different limits. Setting too high refresh rate can mean that FC cannot keep up with the gyro and higher gyro_sync_denom is needed. OFF ON ON Master UINT8
gyro_sync_denom This option determines the sampling ratio. Denominator of 1 means full gyro sampling rate. Denominator 2 would mean ½ samples will be collected. Denominator and gyro_lpf will together determine the control loop speed. 0 32 1 Master UINT8
mid_rc This is an important number to set in order to avoid trimming receiver/transmitter. Most standard receivers will have this at 1500, however Futaba transmitters will need this set to 1520. A way to find out if this needs to be changed, is to clear all trim/subtrim on transmitter, and connect to GUI. Note the value most channels idle at - this should be the number to choose. Once midrc is set, use subtrim on transmitter to make sure all channels (except throttle of course) are centered at midrc value. 1200 1700 1500 Master UINT16
min_check These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. 0 2000 1100 Master UINT16
max_check These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. 0 2000 1900 Master UINT16
rssi_channel RX channel containing the RSSI signal 0 18 0 Master INT8
rssi_scale When using ADC RSSI, the raw ADC value will be divided by rssi_scale in order to get the RSSI percentage. RSSI scale is therefore the ADC raw value for 100% RSSI. 1 255 30 Master UINT8
rssi_ppm_invert When using PWM RSSI, determines if the signal is inverted (Futaba, FrSKY) OFF ON ON Master INT8
rc_smoothing Interpolation of Rc data during looptimes when there are no new updates. This gives smoother RC input to PID controller and cleaner PIDsum OFF ON ON Master INT8
rx_min_usec Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. 750 2250 885 Master UINT16
rx_max_usec Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. 750 2250 2115 Master UINT16
serialrx_provider When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. Possible values: SPEK1024, SPEK2048, SBUS, SUMD, XB-B, XB-B-RJ01, IBUS SPEK1024 Master UINT8
sbus_inversion Standard SBUS (Futaba, FrSKY) uses an inverted signal. Some OpenLRS receivers produce a non-inverted SBUS signal. This setting is to support this type of receivers (including modified FrSKY). This only works on supported hardware (mainly F3 based flight controllers). OFF ON ON Master UINT8
spektrum_sat_bind 0 = disabled. Used to bind the spektrum satellite to RX 0 10 0 Master UINT8
input_filtering_mode Filter out noise from OpenLRS Telemetry RX OFF ON ON Master INT8
min_throttle These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. 0 2000 1150 Master UINT16
max_throttle These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. If you have brushed motors, the value should be set to 2000. 0 2000 1850 Master UINT16
min_command This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. 0 2000 1000 Master UINT16
servo_center_pulse Servo midpoint 0 2000 1500 Master UINT16
motor_pwm_rate Output frequency (in Hz) for motor pins. Defaults are 400Hz for motor. If setting above 500Hz, will switch to brushed (direct drive) motors mode. For example, setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. 50 32000 400 Master UINT16
servo_pwm_rate Output frequency (in Hz) servo pins. Default is 50Hz. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. 50 498 50 Master UINT16
3d_deadband_low Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) 0 2000 1406 Master UINT16
3d_deadband_high High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) 0 2000 1514 Master UINT16
3d_neutral Neutral (stop) throttle value for 3D mode 0 2000 1460 Master UINT16
retarded_arm Disabled by default, enabling (setting to 1) allows disarming by throttle low + roll. This could be useful for mode-1 users and non-acro tricopters, where default arming by yaw could move tail servo too much. OFF ON OFF Master UINT8
disarm_kill_switch Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. OFF ON ON Master UINT8
auto_disarm_delay Delay before automatic disarming 0 60 5 Master UINT8
max_arm_angle Maximum horizontal angle before arming is disabled 0 180 25 Master UINT8
small_angle If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. 0 180 25 Master UINT8
fixedwing_althold_dir Used for fixed-wing aircrafts. Determines of the correction value applied to throttle in alititude hold mode should be inverted. -1 1 1 Master INT8
reboot_character Special character used to trigger reboot 48 126 82 Master UINT8
gps_provider GPS standard. Possible values: NMEA, UBLOX NMEA Master UINT8
gps_sbas_mode Ground assistance type. Possible values: AUTO, EGNOS, WAAS, MSAS, GAGAN AUTO Master UINT8
gps_auto_config Enable automatic configuration of UBlox GPS receivers. OFF ON ON Master UINT8
gps_auto_baud Enable automatic detection of GPS baudrate. OFF ON OFF Master UINT8
gps_pos_p GPS Position hold: P parameter 0 200 15 Profile UINT8
gps_pos_i GPS Position hold: I parameter 0 200 0 Profile UINT8
gps_pos_d GPS Position hold: D parameter 0 200 0 Profile UINT8
gps_posr_p GPS Position hold rate: P parameter 0 200 34 Profile UINT8
gps_posr_i GPS Position hold rate: I parameter 0 200 14 Profile UINT8
gps_posr_d GPS Position hold rate: D parameter 0 200 53 Profile UINT8
gps_nav_p GPS Navigation: P parameter 0 200 25 Profile UINT8
gps_nav_i GPS Navigation: I parameter 0 200 33 Profile UINT8
gps_nav_d GPS Navigation: D parameter 0 200 83 Profile UINT8
gps_wp_radius GPS Navigation: waypoint radius 0 2000 200 Profile UINT16
nav_controls_heading GPS Navigation: should the craft’s heading follow the flying direction. OFF ON ON Profile UINT8
nav_speed_min GPS Navigation: minimum moving speed 10 2000 100 Profile UINT16
nav_speed_max GPS Navigation: maximum moving speed 10 2000 300 Profile UINT16
nav_slew_rate GPS Navigation: maximum angle correction value. Lower slew rate stops the craft from rotating too quickly. 0 100 30 Profile UINT8
telemetry_switch When an AUX channel is used to change serial output & baud rate (MSP / Telemetry). OFF: Telemetry is activated when armed. ON: Telemetry is activated by the AUX channel. OFF ON OFF Master UINT8
telemetry_inversion Determines if the telemetry signal is inverted (Futaba, FrSKY) OFF ON OFF Master UINT8
frsky_default_lattitude OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. -90 90 0 Master FLOAT
frsky_default_longitude OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. -180 180 0 Master FLOAT
frsky_coordinates_format FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA FRSKY_FORMAT_DMS Master UINT8
frsky_unit IMPERIAL (default), METRIC IMPERIAL Master UINT8
frsky_vfas_precision Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method 0 1 0 Master UINT8
hott_alarm_sound_interval Battery alarm delay in seconds for Hott telemetry 0 120 5 Master UINT8
battery_capacity Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. 0 20000 0 Master UINT16
vbat_scale Result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) x 10 for 0.1V. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing “status”“ in cli.” 0 255 110 Master UINT8
vbat_max_cell_voltage Maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V) 10 50 43 Master UINT8
vbat_min_cell_voltage Minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V) 10 50 33 Master UINT8
vbat_warning_cell_voltage Warning voltage per cell, this triggers battery warning alarms, in 0.1V units, default is 35 (3.5V) 10 50 35 Master UINT8
current_meter_scale This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. -10000 10000 400 Master INT16
current_meter_offset This sets the output offset voltage of the current sensor in millivolts. 0 3300 0 Master UINT16
multiwii_current_meter_output Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps). OFF ON OFF Master UINT8
current_meter_type ADC (default), VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. ADC Master UINT8
align_gyro When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0, CW90, CW180, CW270, CW0FLIP, CW90FLIP, CW180FLIP, CW270FLIP. DEFAULT Master UINT8
align_acc When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0, CW90, CW180, CW270, CW0FLIP, CW90FLIP, CW180FLIP, CW270FLIP. DEFAULT Master UINT8
align_mag When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0, CW90, CW180, CW270, CW0FLIP, CW90FLIP, CW180FLIP, CW270FLIP. DEFAULT Master UINT8
align_board_roll Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc -180 360 0 Master INT16
align_board_pitch Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc -180 360 0 Master INT16
align_board_yaw Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc -180 360 0 Master INT16
max_angle_inclination This setting controls max inclination (tilt) allowed in angle (level) mode. default 500 (50 degrees). 100 900 500 Master UINT16
gyro_lpf Hardware lowpass filter cutoff frequency for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ. If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. 10HZ 188HZ 42HZ Master UINT16
gyro_soft_lpf Software lowpass filter cutoff frequency for gyro. Default is 60Hz. Set to 0 to disable. 0 500 60 Master UINT16
moron_threshold When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold (default of 32) means how much average gyro reading could differ before re-calibration is triggered. 0 128 32 Master UINT8
imu_dcm_kp Inertial Measurement Unit KP Gain 0 20000 2500 Master UINT16
imu_dcm_ki Inertial Measurement Unit KI Gain 0 20000 0 Master UINT16
alt_hold_deadband Altitude will be held when throttle is centered with an error margin defined in this parameter. 1 250 40 Profile UINT8
alt_hold_fast_change Authorise fast altitude changes. Should be disabled when slow changes are prefered, for example for aerial photography. OFF ON ON Profile UINT8
deadband These are values (in us) by how much RC input can be different before it’s considered valid for roll and pitch axis. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. This value is applied either side of the centrepoint. 0 32 0 Profile UINT8
yaw_deadband These are values (in us) by how much RC input can be different before it’s considered valid for the yaw axis. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. This value is applied either side of the centrepoint. 0 100 0 Profile UINT8
yaw_control_direction Use if you need to inverse yaw control direction. -1 1 1 Profile INT8
3d_deadband_throttle Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. 0 2000 50 Profile UINT16
throttle_correction_value The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. 0 150 0 Profile UINT8
throttle_correction_angle The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. 1 900 800 Profile UINT16
pid_at_min_throttle If enabled, the copter will process the pid algorithm at minimum throttle. Cannot be used when retarded_arm is enabled. OFF ON ON Master UINT8
yaw_motor_direction Use if you need to inverse yaw motor direction. -1 1 1 Master INT8
yaw_jump_prevention_limit Prevent yaw jumps during yaw stops and rapid YAW input. To disable set to 500. Adjust this if your aircraft 'skids out’. Higher values increases YAW authority but can cause roll/pitch instability in case of underpowered UAVs. Lower values makes yaw adjustments more gentle but can cause UAV unable to keep heading 80 500 200 Master UINT16
tri_unarmed_servo On tricopter mix only, if this is set to 1, servo will always be correcting regardless of armed state. to disable this, set it to 0. OFF ON ON Master INT8
servo_lowpass_freq Selects the servo PWM output cutoff frequency. Valid values range from 10 to 400. This is a fraction of the loop frequency in 1/1000ths. For example, 40 means 0.040. The cutoff frequency can be determined by the following formula: Frequency = 1000 * servo_lowpass_freq / looptime 10 400 400 Master FLOAT
servo_lowpass_enable Disabled by default. OFF ON OFF Master INT8
default_rate_profile Default = profile number 0 2 0 Profile UINT8
rc_rate Rate value for all RC directions 0 250 90 Rate Profile UINT8
rc_expo Exposition value for all RC directions 0 100 65 Rate Profile UINT8
rc_yaw_expo Yaw exposition value 0 100 0 Rate Profile UINT8
thr_mid Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. 0 100 50 Rate Profile UINT8
thr_expo Throttle exposition value 0 100 0 Rate Profile UINT8
roll_rate Roll rate value 100 40 Rate Profile UINT8
pitch_rate Pitch rate value 100 40 Rate Profile UINT8
yaw_rate Yaw rate value 0 255 0 Rate Profile UINT8
tpa_rate Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. 0 100 0 Rate Profile UINT8
tpa_breakpoint See tpa_rate. 1000 2000 1500 Rate Profile UINT16
failsafe_delay Time in deciseconds to wait before activating failsafe when signal is lost. See Failsafe documentation. 0 200 10 Master UINT8
failsafe_off_delay Time in deciseconds to wait before turning off motors when failsafe is activated. See Failsafe documentation. 0 200 200 Master UINT8
failsafe_throttle Throttle level used for landing when failsafe is enabled. See Failsafe documentation. 1000 2000 1000 Master UINT16
failsafe_kill_switch Set to ON to use an AUX channel as a faisafe kill switch. OFF ON OFF Master UINT8
failsafe_throttle_low_delay Activate failsafe when throttle is low and no RX data has been received since this value, in 10th of seconds 0 300 100 Master UINT16
failsafe_procedure 0 = Autolanding (default). 1 = Drop. 0 1 0 Master UINT8
gimbal_mode When feature SERVO_TILT is enabled, this can be either NORMAL or MIXTILT NORMAL Profile UINT8
acc_hardware This is used to suggest which accelerometer driver should load, or to force no accelerometer in case gyro-only flight is needed. Default (0) will attempt to auto-detect among enabled drivers. Otherwise, to force a particular device, set it to 2 for ADXL345, 3 for MPU6050 integrated accelerometer, 4 for MMA8452, 5 for BMA280, 6 for LSM303DLHC, 7 for MPU6000, 8 for MPU6500 or 1 to disable accelerometer alltogether - resulting in gyro-only operation. 0 9 0 Master UINT8
acc_cut_hz Set the Low Pass Filter factor for ACC. Reducing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter 0 200 15 Profile UINT8
accxy_deadband Deadband applied to accelerometrer measurements to reduce integration drift and vibration influence 0 100 40 Profile UINT8
accz_deadband Deadband applied to accelerometrer measurements to reduce integration drift and vibration influence 0 100 40 Profile UINT8
accz_lpf_cutoff Cutoff frequency used in the low-pass filtering of accelerometer measurements. 1 20 5 Profile FLOAT
acc_unarmedcal Determines the method used to calculate gravitational compensation on the Z axis in the Inertial Measurement Unit’s acceleration calculation. The method used when set to ON takes account of the armed status. OFF ON ON Profile UINT8
acc_trim_pitch Accelerometer trim (Pitch) -300 300 0 Profile INT16
acc_trim_roll Accelerometer trim (Roll) -300 300 0 Profile INT16
baro_tab_size Pressure sensor sample count. 0 48 21 Profile UINT8
baro_noise_lpf barometer low-pass filter cut-off frequency in Hz. Ranges from 0 to 1 ; default 0.6 0 1 0.6 Profile FLOAT
baro_cf_vel Velocity sensor mix in altitude hold. Determines the influence accelerometer and barometer sensors have in the velocity estimation. Values from 0 to 1; 1 for pure accelerometer altitude, 0 for pure barometer altitude. 0 1 0.985 Profile FLOAT
baro_cf_alt Altitude sensor mix in altitude hold. Determines the influence accelerometer and barometer sensors have in the altitude estimation. Values from 0 to 1; 1 for pure accelerometer altitude, 0 for pure barometer altitude. 0 1 0.965 Profile FLOAT
baro_hardware 0 = Default, use whatever mag hardware is defined for your board type ; 1 = None, 2 = BMP085, 3 = MS5611, 4 = BMP280 0 4 0 Master UINT8
mag_hardware 0 = Default, use whatever mag hardware is defined for your board type ; 1 = None, disable mag ; 2 = HMC5883 ; 3 = AK8975 ; 4 = AK8963 (for versions <= 1.7.1: 1 = HMC5883 ; 2 = AK8975 ; 3 = None, disable mag) 0 4 0 Master UINT8
mag_declination Current location magnetic declination in dddmm format. For example, -6deg 37min = -637 for Japan. Leading zeros not required. Get your local magnetic declination here: http://magnetic-declination.com/ -18000 18000 0 Profile INT16
pid_controller MW23, MWREWRITE (deafult), LUX MWREWRITE Profile UINT8
p_pitch Pitch P parameter 0 200 40 Profile UINT8
i_pitch Pitch I parameter 0 200 30 Profile UINT8
d_pitch Pitch D parameter 0 200 23 Profile UINT8
p_roll Roll P parameter 0 200 40 Profile UINT8
i_roll Roll I parameter 0 200 30 Profile UINT8
d_roll Roll D parameter 0 200 23 Profile UINT8
p_yaw Yaw P parameter 0 200 85 Profile UINT8
i_yaw Yaw I parameter 0 200 45 Profile UINT8
d_yaw Yaw D parameter 0 200 0 Profile UINT8
p_alt Altitude P parameter (Baro / Sonar altitude hold) 0 200 50 Profile UINT8
i_alt Altitude I parameter (Baro / Sonar altitude hold) 0 200 0 Profile UINT8
d_alt Altitude D parameter (Baro / Sonar altitude hold) 0 200 0 Profile UINT8
p_level Level P parameter (Angle / horizon modes) 0 200 20 Profile UINT8
i_level Level I parameter (Angle / horizon modes) 0 200 10 Profile UINT8
d_level Level D parameter (Angle / horizon modes) 0 200 100 Profile UINT8
p_vel Velocity P parameter (Baro / Sonar altitude hold) 0 200 120 Profile UINT8
i_vel Velocity I parameter (Baro / Sonar altitude hold) 0 200 45 Profile UINT8
d_vel Velocity D parameter (Baro / Sonar altitude hold) 0 200 1 Profile UINT8
yaw_p_limit Limiter for yaw P term. This parameter is only affecting PID controller MW23. To disable set to 500 (actual default). 100 500 500 Profile UINT16
dterm_cut_hz Lowpass cutoff filter for Dterm for all PID controllers 0 500 0 Profile UINT16
gtune_loP_rll GTune: Low Roll P limit 10 200 10 Profile UINT8
gtune_loP_ptch GTune: Low Pitch P limit 10 200 10 Profile UINT8
gtune_loP_yw GTune: Low Yaw P limit 10 200 10 Profile UINT8
gtune_hiP_rll GTune: High Roll P limit 0 200 100 Profile UINT8
gtune_hiP_ptch GTune: High Pitch P limit 0 200 100 Profile UINT8
gtune_hiP_yw GTune: High Yaw P limit 0 200 100 Profile UINT8
gtune_pwr Strength of each Gtune adjustment 0 10 0 Profile UINT8
gtune_settle_time GTune settling time in milliseconds 200 450 Profile UINT16
gtune_average_cycles Looptime cycles for gyro average calculation. Default = 16. 8 128 16 Profile UINT8
blackbox_rate_num Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations 1 32 1 Master UINT8
blackbox_rate_denom Blackbox logging rate denominator. See blackbox_rate_num. 1 32 1 Master UINT8
blackbox_device SERIAL, SPIFLASH, SDCARD (default) SDCARD Master UINT8
magzero_x Magnetometer calibration X offset -32768 32767 0 Master INT16
magzero_y Magnetometer calibration Y offset -32768 32767 0 Master INT16
magzero_z Magnetometer calibration Z offset -32768 32767 0 Master INT16