Skip to main content

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.

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

Accessing The CLI with a Terminal Emulator

The CLI can be accessed via the CLI Tab in 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.

CLI Usage

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

info

Backup and Restore is now supported in the Presets Tab. This method is quicker and does not reqire CLI usage

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

Diff Backup Using CLI

This method shows all user-modified settings but avoids saving values left as default or values that are part of the board targets

Note that diff only shows the current Rate and PID profiles, whereas diff all will show all profiles that have been changed

diff all

This data should be sufficient to replicate the quad configuration on a new or erased flight controller board. Use the save to file function to create a backup

Dump Using CLI

Note that the dump command will output every setting and their current values. Many of these will be firmware defaults and are not needed to backup quad configuration changes

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

info

Backup and Restore is now supported in the Presets Tab. This method is quicker and does not reqire CLI usage

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 you will 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.

info

Some CLI commands or explanations may not exist in your firmware

CommandDescription
1wire <esc>passthrough 1wire to the specified ESC
adjrangeshow/set adjustment ranges settings
auxshow/set aux settings
mmixdesign custom motor mixer
smixdesign custom servo mixer
colorconfigure colors
defaultsreset to defaults and reboot
dumpprint configurable settings in a pastable form
dmaconfigure direct memory access channel
exit
featurelist or -val or val
getget variable value
gpspassthroughpassthrough GPS to serial
help
ledconfigure leds
mapmapping of RC channel order
mixermixer name or list
mode_colorconfigure mode colors
motorget/set motor output value
play_soundindex, or none for next
profileindex (0 to 2)
rateprofileindex (0 to 2)
rxrangeconfigure rx channel ranges (end-points)
rxfailshow/set rx failsafe settings
savesave and reboot
serialpassthroughserial passthrough mode, reset board to exit
setname=value or blank or * for list
statusshow system status
timerconfigure timer
versionshow version
serialconfigure serial ports
servoconfigure servos
sd_infosdcard info
tasksshow task stats

CLI Variable Reference

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

info

Some variable names or explanations may not apply to your firmware, or may be out of date.

Please check the help command and use get <variable name> in the CLI Tab to get the latest information

VariableDescription/UnitsMinMaxDefaultTypeDatatype
mid_rcThis 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.120017001500MasterUINT16
min_checkThese 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.020001100MasterUINT16
max_checkThese 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.020001900MasterUINT16
rssi_channelRX channel containing the RSSI signal0180MasterINT8
rssi_scaleWhen 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.125530MasterUINT8
rssi_invertWhen using PWM RSSI or ADC RSSI, determines if the signal is inverted (Futaba, FrSKY)OFFONONMasterINT8
rc_smoothingInterpolation of Rc data during looptimes when there are no new updates. This gives smoother RC input to PID controller and cleaner PIDsumOFFONONMasterINT8
rx_min_usecDefines 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.7502250885MasterUINT16
rx_max_usecDefines 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.75022502115MasterUINT16
serialrx_providerWhen 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, IBUSSPEK1024MasterUINT8
sbus_inversionStandard 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).OFFONONMasterUINT8
spektrum_sat_bind0 = disabled. Used to bind the spektrum satellite to RX0100MasterUINT8
input_filtering_modeFilter out noise from OpenLRS Telemetry RXOFFONONMasterINT8
min_throttleThese 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.020001150MasterUINT16
max_throttleThese 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.020001850MasterUINT16
min_commandThis 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.020001000MasterUINT16
servo_center_pulseServo midpoint020001500MasterUINT16
motor_pwm_rateOutput 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.5032000400MasterUINT16
servo_pwm_rateOutput 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.5049850MasterUINT16
3d_deadband_lowLow 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)020001406MasterUINT16
3d_deadband_highHigh value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)020001514MasterUINT16
3d_neutralNeutral (stop) throttle value for 3D mode020001460MasterUINT16
auto_disarm_delayDelay before automatic disarming0605MasterUINT8
small_angleIf the copter tilt angle exceed this value the copter will refuse to arm. default is 25°.018025MasterUINT8
reboot_characterSpecial character used to trigger reboot4812682MasterUINT8
gps_providerGPS standard. Possible values: NMEA, UBLOXNMEAMasterUINT8
gps_sbas_modeGround assistance type. Possible values: AUTO, EGNOS, WAAS, MSAS, GAGANAUTOMasterUINT8
gps_auto_configEnable automatic configuration of UBlox GPS receivers.OFFONONMasterUINT8
gps_auto_baudEnable automatic detection of GPS baudrate.OFFONOFFMasterUINT8
report_cell_voltageDetermines if the voltage reported is Vbatt or calculated average cell voltage.OFFONOFFMasterUINT8
telemetry_inversionDetermines if the telemetry signal is inverted (Futaba, FrSKY)OFFONOFFMasterUINT8
frsky_default_latOpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired.-90900MasterFLOAT
frsky_default_longOpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired.-1801800MasterFLOAT
frsky_gps_formatFRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEAFRSKY_FORMAT_DMSMasterUINT8
frsky_unitIMPERIAL (default), METRICIMPERIALMasterUINT8
frsky_vfas_precisionSet to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method010MasterUINT8
hott_alarm_intBattery alarm delay in seconds for Hott telemetry01205MasterUINT8
bat_capacityBattery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity.0200000MasterUINT16
vbat_scaleResult 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.0255110MasterUINT8
vbat_max_cell_voltageMaximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 430 (4.3V)100500430MasterUINT16
vbat_min_cell_voltageMinimum voltage per cell, this triggers battery-critical alarms, in 0.01V units, default is 330 (3.3V)100500330MasterUINT16
vbat_warning_cell_voltageWarning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)100500350MasterUINT16
vbat_hysteresisSets the hysteresis value for low-battery alarms, in 0.01V units, default is 1 (0.01V)102501MasterUINT8
ibata_scaleThis 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.-1000010000400MasterINT16
ibata_offsetThis sets the output offset voltage of the current sensor in millivolts.033000MasterUINT16
current_meter_typeADC (default), VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position.ADCMasterUINT8
align_board_rollArbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc-1803600MasterINT16
align_board_pitchArbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc-1803600MasterINT16
align_board_yawArbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc-1803600MasterINT16
gyro_calib_noise_thresholdWhen 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.012832MasterUINT8
imu_dcm_kpInertial Measurement Unit KP Gain0200002500MasterUINT16
imu_dcm_kiInertial Measurement Unit KI Gain0200000MasterUINT16
3d_deadband_throttleThrottle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter.0200050ProfileUINT16
servo_lowpass_hzSelects 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 / looptime10400400MasterFLOAT
rate_profileDefault = profile number020ProfileUINT8
rc_rateRate value for all RC directions025090Rate ProfileUINT8
rc_expoExposition value for all RC directions010065Rate ProfileUINT8
rc_yaw_expoYaw exposition value01000Rate ProfileUINT8
thr_midThrottle value when the stick is set to mid-position. Used in the throttle curve calculation.010050Rate ProfileUINT8
thr_expoThrottle exposition value01000Rate ProfileUINT8
roll_rateRoll rate value10040Rate ProfileUINT8
pitch_ratePitch rate value10040Rate ProfileUINT8
yaw_rateYaw rate value02550Rate ProfileUINT8
tpa_rateThrottle 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.01000Rate ProfileUINT8
tpa_breakpointSee tpa_rate.100020001500Rate ProfileUINT16
failsafe_delayTime in deciseconds to wait before activating failsafe when signal is lost. See Failsafe documentation.020010MasterUINT8
failsafe_off_delayTime in deciseconds to wait before turning off motors when failsafe is activated. See Failsafe documentation.0200200MasterUINT8
failsafe_throttleThrottle level used for landing when failsafe is enabled. See Failsafe documentation.100020001000MasterUINT16
failsafe_kill_switchSet to ON to use an AUX channel as a faisafe kill switch.OFFONOFFMasterUINT8
failsafe_throttle_low_delayActivate failsafe when throttle is low and no RX data has been received since this value, in 10th of seconds0300100MasterUINT16
failsafe_procedure0 = Autolanding (default). 1 = Drop.010MasterUINT8
gimbal_modeWhen feature SERVO_TILT is enabled, this can be either NORMAL or MIXTILTNORMALProfileUINT8
acc_hardwareThis 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.090MasterUINT8
accz_lpf_cutoffCutoff frequency used in the low-pass filtering of accelerometer measurements.1205ProfileFLOAT
acc_trim_pitchAccelerometer trim (Pitch)-3003000ProfileINT16
acc_trim_rollAccelerometer trim (Roll)-3003000ProfileINT16
p_pitchPitch P parameter020040ProfileUINT8
i_pitchPitch I parameter020030ProfileUINT8
d_pitchPitch D parameter020023ProfileUINT8
p_roll Roll P parameter020040ProfileUINT8
i_roll Roll I parameter020030ProfileUINT8
d_roll Roll D parameter020023ProfileUINT8
p_yawYaw P parameter020085ProfileUINT8
i_yawYaw I parameter020045ProfileUINT8
d_yawYaw D parameter02000ProfileUINT8
p_altAltitude P parameter (Baro / Sonar altitude hold)020050ProfileUINT8
i_altAltitude I parameter (Baro / Sonar altitude hold)02000ProfileUINT8
d_altAltitude D parameter (Baro / Sonar altitude hold)02000ProfileUINT8
p_levelLevel P parameter (Angle / horizon modes)020020ProfileUINT8
i_levelLevel I parameter (Angle / horizon modes)020010ProfileUINT8
d_levelLevel D parameter (Angle / horizon modes)0200100ProfileUINT8
p_velVelocity P parameter (Baro / Sonar altitude hold)0200120ProfileUINT8
i_velVelocity I parameter (Baro / Sonar altitude hold)020045ProfileUINT8
d_velVelocity D parameter (Baro / Sonar altitude hold)02001ProfileUINT8
yaw_p_limitLimiter for yaw P term. This parameter is only affecting PID controller MW23. To disable set to 500 (actual default).100500500ProfileUINT16
dterm_cut_hzLowpass cutoff filter for Dterm for all PID controllers05000ProfileUINT16
blackbox_rate_numBlackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations1321MasterUINT8
blackbox_rate_denomBlackbox logging rate denominator. See blackbox_rate_num.1321MasterUINT8
blackbox_deviceSERIAL, SPIFLASH, SDCARD (default)SDCARDMasterUINT8
magzero_xMagnetometer calibration X offset-32768327670MasterINT16
magzero_yMagnetometer calibration Y offset-32768327670MasterINT16
magzero_zMagnetometer calibration Z offset-32768327670MasterINT16
vtx_bandConfigure the VTX band. Set to zero to use vtx_freq. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race.054MasterUINT8
vtx_channelChannel to use within the configured vtx_band. Valid values are [1, 8].181MasterUINT8
vtx_freqSet the VTX frequency using raw MHz. This parameter is ignored unless vtx_band is 0.059005740MasterUINT16
vtx_halfduplexUse half duplex UART to communicate with the VTX, using only a TX pin in the FC.OFFONONMasterUINT8
vtx_low_power_disarmWhen the craft is disarmed, set the VTX to its lowest power. ON will set the power to its minimum value on startup, increase it to vtx_power when arming and change it back to its lowest setting after disarming. UNTIL_FIRST_ARM will start with minimum power, but once the craft is armed it will increase to vtx_power and it will never decrease until the craft is power cycled.OFFMasterUINT8
vtx_pit_mode_freqFrequency to use (in MHz) when the VTX is in pit mode.059000MasterUINT16
vtx_powerVTX RF power level to use. The exact number of mw depends on the VTX hardware.031MasterUINT8