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.
- Connect your terminal emulator to the CLI serial port (which, by default, is the same as the MSP serial port)
- Use the baudrate specified by msp_baudrate (115200 by default).
- 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
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
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.
Some CLI commands or explanations may not exist in your firmware
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 |
dma | configure direct memory access channel |
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 |
serialpassthrough | serial passthrough mode, reset board to exit |
set | name=value or blank or * for list |
status | show system status |
timer | configure timer |
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.
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
Variable | Description/Units | Min | Max | Default | Type | Datatype |
---|---|---|---|---|---|---|
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_invert | When using PWM RSSI or ADC 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 |
auto_disarm_delay | Delay before automatic disarming | 0 | 60 | 5 | 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 |
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 |
report_cell_voltage | Determines if the voltage reported is Vbatt or calculated average cell voltage. | OFF | ON | OFF | Master | UINT8 |
telemetry_inversion | Determines if the telemetry signal is inverted (Futaba, FrSKY) | OFF | ON | OFF | Master | UINT8 |
frsky_default_lat | 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_long | 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_gps_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_int | Battery alarm delay in seconds for Hott telemetry | 0 | 120 | 5 | Master | UINT8 |
bat_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.01V units, default is 430 (4.3V) | 100 | 500 | 430 | Master | UINT16 |
vbat_min_cell_voltage | Minimum voltage per cell, this triggers battery-critical alarms, in 0.01V units, default is 330 (3.3V) | 100 | 500 | 330 | Master | UINT16 |
vbat_warning_cell_voltage | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | 100 | 500 | 350 | Master | UINT16 |
vbat_hysteresis | Sets the hysteresis value for low-battery alarms, in 0.01V units, default is 1 (0.01V) | 10 | 250 | 1 | Master | UINT8 |
ibata_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 |
ibata_offset | This sets the output offset voltage of the current sensor in millivolts. | 0 | 3300 | 0 | Master | UINT16 |
current_meter_type | ADC (default), VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | ADC | 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 |
gyro_calib_noise_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 |
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 |
servo_lowpass_hz | 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 |
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 |
accz_lpf_cutoff | Cutoff frequency used in the low-pass filtering of accelerometer measurements. | 1 | 20 | 5 | Profile | FLOAT |
acc_trim_pitch | Accelerometer trim (Pitch) | -300 | 300 | 0 | Profile | INT16 |
acc_trim_roll | Accelerometer trim (Roll) | -300 | 300 | 0 | Profile | INT16 |
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 |
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 |
vtx_band | Configure the VTX band. Set to zero to use vtx_freq . Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | 0 | 5 | 4 | Master | UINT8 |
vtx_channel | Channel to use within the configured vtx_band . Valid values are [1, 8]. | 1 | 8 | 1 | Master | UINT8 |
vtx_freq | Set the VTX frequency using raw MHz. This parameter is ignored unless vtx_band is 0. | 0 | 5900 | 5740 | Master | UINT16 |
vtx_halfduplex | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | OFF | ON | ON | Master | UINT8 |
vtx_low_power_disarm | When 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. | OFF | Master | UINT8 | ||
vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. | 0 | 5900 | 0 | Master | UINT16 |
vtx_power | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | 0 | 3 | 1 | Master | UINT8 |