2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
27 #include "scheduler.h"
30 #include "build_config.h"
32 #include "common/axis.h"
33 #include "common/maths.h"
34 #include "common/color.h"
35 #include "common/typeconversion.h"
37 #include "drivers/system.h"
39 #include "drivers/sensor.h"
40 #include "drivers/accgyro.h"
41 #include "drivers/compass.h"
43 #include "drivers/serial.h"
44 #include "drivers/bus_i2c.h"
45 #include "drivers/gpio.h"
46 #include "drivers/timer.h"
47 #include "drivers/pwm_rx.h"
50 #include "io/escservo.h"
52 #include "io/gimbal.h"
53 #include "io/rc_controls.h"
54 #include "io/serial.h"
55 #include "io/ledstrip.h"
56 #include "io/flashfs.h"
57 #include "io/beeper.h"
60 #include "rx/spektrum.h"
62 #include "sensors/battery.h"
63 #include "sensors/boardalignment.h"
64 #include "sensors/sensors.h"
65 #include "sensors/acceleration.h"
66 #include "sensors/gyro.h"
67 #include "sensors/compass.h"
68 #include "sensors/barometer.h"
70 #include "flight/pid.h"
71 #include "flight/imu.h"
72 #include "flight/mixer.h"
73 #include "flight/navigation_rewrite.h"
74 #include "flight/failsafe.h"
76 #include "telemetry/telemetry.h"
77 #include "telemetry/frsky.h"
79 #include "config/runtime_config.h"
80 #include "config/config.h"
81 #include "config/config_profile.h"
82 #include "config/config_master.h"
84 #include "common/printf.h"
86 #include "serial_cli.h"
88 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
89 // signal that we're in cli mode
94 extern uint16_t cycleTime
; // FIXME dependency on mw.c
96 void gpsEnablePassthrough(serialPort_t
*gpsPassthroughPort
);
98 static serialPort_t
*cliPort
;
100 static void cliAux(char *cmdline
);
101 static void cliRxFail(char *cmdline
);
102 static void cliAdjustmentRange(char *cmdline
);
103 static void cliMotorMix(char *cmdline
);
104 static void cliDefaults(char *cmdline
);
105 static void cliDump(char *cmdLine
);
106 static void cliExit(char *cmdline
);
107 static void cliFeature(char *cmdline
);
108 static void cliMotor(char *cmdline
);
109 static void cliPlaySound(char *cmdline
);
110 static void cliProfile(char *cmdline
);
111 static void cliRateProfile(char *cmdline
);
112 static void cliReboot(void);
113 static void cliSave(char *cmdline
);
114 static void cliSerial(char *cmdline
);
117 static void cliServo(char *cmdline
);
118 static void cliServoMix(char *cmdline
);
121 static void cliSet(char *cmdline
);
122 static void cliGet(char *cmdline
);
123 static void cliStatus(char *cmdline
);
124 #ifndef SKIP_TASK_STATISTICS
125 static void cliTasks(char *cmdline
);
127 static void cliVersion(char *cmdline
);
128 static void cliRxRange(char *cmdline
);
129 static void cliPFlags(char *cmdline
);
133 static void cliGpsPassthrough(char *cmdline
);
136 static void cliHelp(char *cmdline
);
137 static void cliMap(char *cmdline
);
140 static void cliLed(char *cmdline
);
141 static void cliColor(char *cmdline
);
144 #ifndef USE_QUAD_MIXER_ONLY
145 static void cliMixer(char *cmdline
);
149 static void cliFlashInfo(char *cmdline
);
150 static void cliFlashErase(char *cmdline
);
151 #ifdef USE_FLASH_TOOLS
152 static void cliFlashWrite(char *cmdline
);
153 static void cliFlashRead(char *cmdline
);
158 static char cliBuffer
[48];
159 static uint32_t bufferIndex
= 0;
161 #ifndef USE_QUAD_MIXER_ONLY
162 // this with mixerMode_e
163 static const char * const mixerNames
[] = {
164 "TRI", "QUADP", "QUADX", "BI",
165 "GIMBAL", "Y6", "HEX6",
166 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
167 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
168 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
169 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
173 // sync this with features_e
174 static const char * const featureNames
[] = {
175 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
176 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
177 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
178 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
179 "BLACKBOX", "CHANNEL_FORWARDING", NULL
182 // sync this with rxFailsafeChannelMode_e
183 static const char rxFailsafeModeCharacters
[] = "ahs";
185 static const rxFailsafeChannelMode_e rxFailsafeModesTable
[RX_FAILSAFE_TYPE_COUNT
][RX_FAILSAFE_MODE_COUNT
] = {
186 { RX_FAILSAFE_MODE_AUTO
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_INVALID
},
187 { RX_FAILSAFE_MODE_INVALID
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
}
191 // sync this with sensors_e
192 static const char * const sensorTypeNames
[] = {
193 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
196 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
198 static const char * const sensorHardwareNames
[4][11] = {
199 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL
},
200 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL
},
201 { "", "None", "BMP085", "MS5611", "BMP280", "FAKE", NULL
},
202 { "", "None", "HMC5883", "AK8975", "FAKE", NULL
}
208 #ifndef SKIP_CLI_COMMAND_HELP
209 const char *description
;
212 void (*func
)(char *cmdline
);
215 #ifndef SKIP_CLI_COMMAND_HELP
216 #define CLI_COMMAND_DEF(name, description, args, method) \
224 #define CLI_COMMAND_DEF(name, description, args, method) \
231 // should be sorted a..z for bsearch()
232 const clicmd_t cmdTable
[] = {
233 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL
, cliAdjustmentRange
),
234 CLI_COMMAND_DEF("aux", "configure modes", NULL
, cliAux
),
236 CLI_COMMAND_DEF("color", "configure colors", NULL
, cliColor
),
238 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL
, cliDefaults
),
239 CLI_COMMAND_DEF("dump", "dump configuration",
240 "[master|profile]", cliDump
),
241 CLI_COMMAND_DEF("exit", NULL
, NULL
, cliExit
),
242 CLI_COMMAND_DEF("feature", "configure features",
244 "\t<+|->[name]", cliFeature
),
246 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL
, cliFlashErase
),
247 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL
, cliFlashInfo
),
248 #ifdef USE_FLASH_TOOLS
249 CLI_COMMAND_DEF("flash_read", NULL
, "<length> <address>", cliFlashRead
),
250 CLI_COMMAND_DEF("flash_write", NULL
, "<address> <message>", cliFlashWrite
),
253 CLI_COMMAND_DEF("get", "get variable value",
256 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL
, cliGpsPassthrough
),
258 CLI_COMMAND_DEF("help", NULL
, NULL
, cliHelp
),
260 CLI_COMMAND_DEF("led", "configure leds", NULL
, cliLed
),
262 CLI_COMMAND_DEF("map", "configure rc channel order",
264 #ifndef USE_QUAD_MIXER_ONLY
265 CLI_COMMAND_DEF("mixer", "configure mixer",
267 "\t<name>", cliMixer
),
269 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL
, cliMotorMix
),
270 CLI_COMMAND_DEF("motor", "get/set motor",
271 "<index> [<value>]", cliMotor
),
272 CLI_COMMAND_DEF("play_sound", NULL
,
273 "[<index>]\r\n", cliPlaySound
),
274 CLI_COMMAND_DEF("profile", "change profile",
275 "[<index>]", cliProfile
),
276 CLI_COMMAND_DEF("rateprofile", "change rate profile",
277 "[<index>]", cliRateProfile
),
278 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL
, cliRxRange
),
279 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL
, cliRxFail
),
280 CLI_COMMAND_DEF("save", "save and reboot", NULL
, cliSave
),
281 CLI_COMMAND_DEF("serial", "configure serial ports", NULL
, cliSerial
),
283 CLI_COMMAND_DEF("servo", "configure servos", NULL
, cliServo
),
285 CLI_COMMAND_DEF("set", "change setting",
286 "[<name>=<value>]", cliSet
),
287 CLI_COMMAND_DEF("pflags", "get persistent flags", NULL
, cliPFlags
),
289 CLI_COMMAND_DEF("smix", "servo mixer",
290 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
293 "\treverse <servo> <source> r|n", cliServoMix
),
295 CLI_COMMAND_DEF("status", "show status", NULL
, cliStatus
),
296 #ifndef SKIP_TASK_STATISTICS
297 CLI_COMMAND_DEF("tasks", "show task stats", NULL
, cliTasks
),
299 CLI_COMMAND_DEF("version", "show version", NULL
, cliVersion
),
301 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
303 static const char * const lookupTableOffOn
[] = {
307 static const char * const lookupTableUnit
[] = {
311 static const char * const lookupTableAlignment
[] = {
324 static const char * const lookupTableGPSProvider
[] = {
325 "NMEA", "UBLOX", "I2C-NAV", "NAZA"
328 static const char * const lookupTableGPSSBASMode
[] = {
329 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
332 static const char * const lookupTableGpsModel
[] = {
337 static const char * const lookupTableCurrentSensor
[] = {
338 "NONE", "ADC", "VIRTUAL"
341 static const char * const lookupTableGimbalMode
[] = {
345 static const char * const lookupTablePidController
[] = {
346 "UNUSED", "MWREWRITE", "LUX"
349 static const char * const lookupTableBlackboxDevice
[] = {
353 static const char * const lookupTableSerialRX
[] = {
364 static const char * const lookupTableGyroFilter
[] = {
365 "OFF", "LOW", "MEDIUM", "HIGH"
368 static const char * const lookupTableGyroLpf
[] = {
377 static const char * const lookupTableSoftFilter
[] = {
378 "OFF", "LOW", "MEDIUM", "HIGH"
381 static const char * const lookupTableFailsafeProcedure
[] = {
382 "SET-THR", "DROP", "RTH"
386 static const char * const lookupTableNavControlMode
[] = {
390 static const char * const lookupTableNavRthAltMode
[] = {
391 "CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST"
395 typedef struct lookupTableEntry_s
{
396 const char * const *values
;
397 const uint8_t valueCount
;
398 } lookupTableEntry_t
;
410 TABLE_BLACKBOX_DEVICE
,
412 TABLE_CURRENT_SENSOR
,
414 TABLE_PID_CONTROLLER
,
418 TABLE_FAILSAFE_PROCEDURE
,
420 TABLE_NAV_USER_CTL_MODE
,
421 TABLE_NAV_RTH_ALT_MODE
,
423 } lookupTableIndex_e
;
425 static const lookupTableEntry_t lookupTables
[] = {
426 { lookupTableOffOn
, sizeof(lookupTableOffOn
) / sizeof(char *) },
427 { lookupTableUnit
, sizeof(lookupTableUnit
) / sizeof(char *) },
428 { lookupTableAlignment
, sizeof(lookupTableAlignment
) / sizeof(char *) },
430 { lookupTableGPSProvider
, sizeof(lookupTableGPSProvider
) / sizeof(char *) },
431 { lookupTableGPSSBASMode
, sizeof(lookupTableGPSSBASMode
) / sizeof(char *) },
432 { lookupTableGpsModel
, sizeof(lookupTableGpsModel
) / sizeof(char *) },
435 { lookupTableBlackboxDevice
, sizeof(lookupTableBlackboxDevice
) / sizeof(char *) },
437 { lookupTableCurrentSensor
, sizeof(lookupTableCurrentSensor
) / sizeof(char *) },
438 { lookupTableGimbalMode
, sizeof(lookupTableGimbalMode
) / sizeof(char *) },
439 { lookupTablePidController
, sizeof(lookupTablePidController
) / sizeof(char *) },
440 { lookupTableSerialRX
, sizeof(lookupTableSerialRX
) / sizeof(char *) },
441 { lookupTableSoftFilter
, sizeof(lookupTableSoftFilter
) / sizeof(char *) },
442 { lookupTableGyroLpf
, sizeof(lookupTableGyroLpf
) / sizeof(char *) },
443 { lookupTableFailsafeProcedure
, sizeof(lookupTableFailsafeProcedure
) / sizeof(char *) },
445 { lookupTableNavControlMode
, sizeof(lookupTableNavControlMode
) / sizeof(char *) },
446 { lookupTableNavRthAltMode
, sizeof(lookupTableNavRthAltMode
) / sizeof(char *) },
450 #define VALUE_TYPE_OFFSET 0
451 #define VALUE_SECTION_OFFSET 4
452 #define VALUE_MODE_OFFSET 6
456 VAR_UINT8
= (0 << VALUE_TYPE_OFFSET
),
457 VAR_INT8
= (1 << VALUE_TYPE_OFFSET
),
458 VAR_UINT16
= (2 << VALUE_TYPE_OFFSET
),
459 VAR_INT16
= (3 << VALUE_TYPE_OFFSET
),
460 VAR_UINT32
= (4 << VALUE_TYPE_OFFSET
),
461 VAR_FLOAT
= (5 << VALUE_TYPE_OFFSET
),
464 MASTER_VALUE
= (0 << VALUE_SECTION_OFFSET
),
465 PROFILE_VALUE
= (1 << VALUE_SECTION_OFFSET
),
466 CONTROL_RATE_VALUE
= (2 << VALUE_SECTION_OFFSET
),
469 MODE_DIRECT
= (0 << VALUE_MODE_OFFSET
),
470 MODE_LOOKUP
= (1 << VALUE_MODE_OFFSET
)
473 #define VALUE_TYPE_MASK (0x0F)
474 #define VALUE_SECTION_MASK (0x30)
475 #define VALUE_MODE_MASK (0xC0)
477 typedef struct cliMinMaxConfig_s
{
482 typedef struct cliLookupTableConfig_s
{
483 const lookupTableIndex_e tableIndex
;
484 } cliLookupTableConfig_t
;
487 cliLookupTableConfig_t lookup
;
488 cliMinMaxConfig_t minmax
;
494 const uint8_t type
; // see cliValueFlag_e
496 const cliValueConfig_t config
;
497 const persistent_flags_e pflags_to_set
;
500 const clivalue_t valueTable
[] = {
501 { "looptime", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.looptime
, .config
.minmax
= {0, 9000}, 0 },
502 { "emf_avoidance", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.emf_avoidance
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
503 { "i2c_overclock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.i2c_overclock
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
504 { "gyro_sync", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyroSync
, .config
.lookup
= { TABLE_OFF_ON
} },
505 { "gyro_sync_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroSyncDenominator
, .config
.minmax
= { 1, 32 } },
507 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.midrc
, .config
.minmax
= { 1200, 1700 }, 0 },
508 { "min_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.mincheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
509 { "max_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.maxcheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
510 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_channel
, .config
.minmax
= { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, 0 },
511 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_scale
, .config
.minmax
= { RSSI_SCALE_MIN
, RSSI_SCALE_MAX
}, 0 },
512 { "rssi_ppm_invert", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rssi_ppm_invert
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
513 { "rc_smoothing", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rcSmoothing
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
514 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.inputFilteringMode
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
516 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.minthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
517 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.maxthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
518 { "min_command", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.mincommand
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
519 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.servoCenterPulse
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
521 { "3d_deadband_low", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_low
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 }, // FIXME upper limit should match code in the mixer, 1500 currently
522 { "3d_deadband_high", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_high
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 }, // FIXME lower limit should match code in the mixer, 1500 currently,
523 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.neutral3d
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
524 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_throttle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
526 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motor_pwm_rate
, .config
.minmax
= { 50, 32000 }, 0 },
527 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servo_pwm_rate
, .config
.minmax
= { 50, 498 }, 0 },
529 { "disarm_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.disarm_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
530 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.auto_disarm_delay
, .config
.minmax
= { 0, 60 }, 0 },
531 { "small_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.small_angle
, .config
.minmax
= { 0, 180 }, 0 },
533 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.serialConfig
.reboot_character
, .config
.minmax
= { 48, 126 }, 0 },
536 { "gps_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.provider
, .config
.lookup
= { TABLE_GPS_PROVIDER
}, 0 },
537 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.sbasMode
, .config
.lookup
= { TABLE_GPS_SBAS_MODE
}, 0 },
538 { "gps_nav_model", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.navModel
, .config
.lookup
= { TABLE_GPS_NAV_MODEL
}, 0 },
539 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoConfig
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
540 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoBaud
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
544 { "nav_alt_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
545 { "nav_alt_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
546 { "nav_alt_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
548 { "nav_vel_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
549 { "nav_vel_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
550 { "nav_vel_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
552 { "nav_pos_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
553 { "nav_pos_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
554 { "nav_pos_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
555 { "nav_posr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
556 { "nav_posr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
557 { "nav_posr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
558 { "nav_navr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
559 { "nav_navr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
560 { "nav_navr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
562 #if defined(INAV_ENABLE_AUTO_MAG_DECLINATION)
563 { "inav_auto_mag_decl", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.automatic_mag_declination
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
566 { "inav_accz_unarmedcal", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.accz_unarmed_cal
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
567 { "inav_use_gps_velned", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.use_gps_velned
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
568 { "inav_gps_delay", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.gps_delay_ms
, .config
.minmax
= { 0, 500 }, 0 },
569 { "inav_gps_min_sats", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.gps_min_sats
, .config
.minmax
= { 5, 10}, 0 },
571 { "inav_w_z_baro_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_baro_p
, .config
.minmax
= { 0, 10 }, 0 },
572 { "inav_w_z_gps_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_gps_p
, .config
.minmax
= { 0, 10 }, 0 },
573 { "inav_w_z_gps_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_gps_v
, .config
.minmax
= { 0, 10 }, 0 },
574 { "inav_w_xy_gps_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_gps_p
, .config
.minmax
= { 0, 10 }, 0 },
575 { "inav_w_xy_gps_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_gps_v
, .config
.minmax
= { 0, 10 }, 0 },
576 { "inav_w_z_res_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_res_v
, .config
.minmax
= { 0, 10 }, 0 },
577 { "inav_w_xy_res_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_res_v
, .config
.minmax
= { 0, 10 }, 0 },
578 { "inav_w_acc_bias", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_acc_bias
, .config
.minmax
= { 0, 1 }, 0 },
580 { "inav_max_eph_epv", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.max_eph_epv
, .config
.minmax
= { 0, 9999 }, 0 },
581 { "inav_baro_epv", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.baro_epv
, .config
.minmax
= { 0, 9999 }, 0 },
583 { "nav_use_midrc_for_althold", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.use_midrc_for_althold
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
584 { "nav_extra_arming_safety", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.extra_arming_safety
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
585 { "nav_user_control_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.user_control_mode
, .config
.lookup
= { TABLE_NAV_USER_CTL_MODE
}, 0 },
586 { "nav_position_timeout", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.pos_failure_timeout
, .config
.minmax
= { 0, 10 }, 0 },
587 { "nav_wp_radius", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.waypoint_radius
, .config
.minmax
= { 100, 10000 }, 0 },
588 { "nav_max_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_speed
, .config
.minmax
= { 10, 2000 }, 0 },
589 { "nav_manual_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_manual_speed
, .config
.minmax
= { 10, 2000 }, 0 },
590 { "nav_manual_climb_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_manual_climb_rate
, .config
.minmax
= { 10, 2000 }, 0 },
591 { "nav_landing_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.land_descent_rate
, .config
.minmax
= { 100, 2000 }, 0 },
592 { "nav_emerg_landing_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.emerg_descent_rate
, .config
.minmax
= { 100, 2000 }, 0 },
593 { "nav_min_rth_distance", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.min_rth_distance
, .config
.minmax
= { 0, 5000 }, 0 },
594 { "nav_rth_tail_first", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.rth_tail_first
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
595 { "nav_rth_alt_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.rth_alt_control_style
, .config
.lookup
= { TABLE_NAV_RTH_ALT_MODE
}, 0 },
596 { "nav_rth_altitude", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.rth_altitude
, .config
.minmax
= { 100, 10000 }, 0 },
598 { "nav_mc_bank_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_max_bank_angle
, .config
.minmax
= { 15, 45 }, 0 },
599 { "nav_mc_hover_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_hover_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
600 { "nav_mc_min_fly_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_min_fly_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
602 { "nav_fw_cruise_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_cruise_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
603 { "nav_fw_min_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_min_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
604 { "nav_fw_max_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
605 { "nav_fw_bank_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_bank_angle
, .config
.minmax
= { 5, 45 }, 0 },
606 { "nav_fw_climb_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_climb_angle
, .config
.minmax
= { 5, 45 }, 0 },
607 { "nav_fw_dive_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_dive_angle
, .config
.minmax
= { 5, 45 }, 0 },
608 { "nav_fw_pitch2thr", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_pitch_to_throttle
, .config
.minmax
= { 0, 100 }, 0 },
611 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.serialrx_provider
, .config
.lookup
= { TABLE_SERIAL_RX
}, 0 },
612 { "spektrum_sat_bind", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.spektrum_sat_bind
, .config
.minmax
= { SPEKTRUM_SAT_BIND_DISABLED
, SPEKTRUM_SAT_BIND_MAX
}, 0 },
614 { "telemetry_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
615 { "telemetry_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_inversion
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
616 { "frsky_default_lattitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLatitude
, .config
.minmax
= { -90.0, 90.0 }, 0 },
617 { "frsky_default_longitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLongitude
, .config
.minmax
= { -180.0, 180.0 }, 0 },
618 { "frsky_coordinates_format", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_coordinate_format
, .config
.minmax
= { 0, FRSKY_FORMAT_NMEA
}, 0 },
619 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.frsky_unit
, .config
.lookup
= { TABLE_UNIT
}, 0 },
620 { "frsky_vfas_precision", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_vfas_precision
, .config
.minmax
= { FRSKY_VFAS_PRECISION_LOW
, FRSKY_VFAS_PRECISION_HIGH
}, 0 },
621 { "hott_alarm_sound_interval", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.hottAlarmSoundInterval
, .config
.minmax
= { 0, 120 }, 0 },
623 { "battery_capacity", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.batteryCapacity
, .config
.minmax
= { 0, 20000 }, 0 },
624 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatscale
, .config
.minmax
= { VBAT_SCALE_MIN
, VBAT_SCALE_MAX
}, 0 },
625 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmaxcellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
626 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmincellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
627 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatwarningcellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
628 { "current_meter_scale", VAR_INT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterScale
, .config
.minmax
= { -10000, 10000 }, 0 },
629 { "current_meter_offset", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterOffset
, .config
.minmax
= { 0, 3300 }, 0 },
630 { "multiwii_current_meter_output", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.multiwiiCurrentMeterOutput
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
631 { "current_meter_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.currentMeterType
, .config
.lookup
= { TABLE_CURRENT_SENSOR
}, 0 },
633 { "align_gyro", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.gyro_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
634 { "align_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.acc_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
635 { "align_mag", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.mag_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
637 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.rollDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
638 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.pitchDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
639 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.yawDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
641 { "max_angle_inclination", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.max_angle_inclination
, .config
.minmax
= { 100, 900 }, 0 },
643 { "gyro_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyro_lpf
, .config
.lookup
= { TABLE_GYRO_LPF
} },
644 { "moron_threshold", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyroMovementCalibrationThreshold
, .config
.minmax
= { 0, 128 }, 0 },
646 { "imu_dcm_kp", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_kp_acc
, .config
.minmax
= { 0, 65535 }, 0 },
647 { "imu_dcm_ki", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_ki_acc
, .config
.minmax
= { 0, 65535 }, 0 },
648 { "imu_dcm_kp_mag", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_kp_mag
, .config
.minmax
= { 0, 65535 }, 0 },
649 { "imu_dcm_ki_mag", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_ki_mag
, .config
.minmax
= { 0, 65535 }, 0 },
651 { "deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.deadband
, .config
.minmax
= { 0, 32 }, 0 },
652 { "yaw_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.yaw_deadband
, .config
.minmax
= { 0, 100 }, 0 },
653 { "pos_hold_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.pos_hold_deadband
, .config
.minmax
= { 10, 250 }, 0 },
654 { "alt_hold_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.alt_hold_deadband
, .config
.minmax
= { 10, 250 }, 0 },
656 { "throttle_tilt_comp_str", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].throttle_tilt_compensation_strength
, .config
.minmax
= { 0, 100 }, 0 },
658 { "yaw_control_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.yaw_control_direction
, .config
.minmax
= { -1, 1 }, 0 },
660 { "yaw_motor_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_motor_direction
, .config
.minmax
= { -1, 1 }, 0 },
661 { "yaw_jump_prevention_limit", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_jump_prevention_limit
, .config
.minmax
= { YAW_JUMP_PREVENTION_LIMIT_LOW
, YAW_JUMP_PREVENTION_LIMIT_HIGH
}, 0 },
664 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.mixerConfig
.tri_unarmed_servo
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
665 { "servo_lowpass_freq", VAR_INT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.servo_lowpass_freq
, .config
.minmax
= { 10, 400}, 0 },
666 { "servo_lowpass_enable", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.mixerConfig
.servo_lowpass_enable
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
669 { "default_rate_profile", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].defaultRateProfileIndex
, .config
.minmax
= { 0, MAX_CONTROL_RATE_PROFILE_COUNT
- 1 }, 0 },
670 { "rc_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcRate8
, .config
.minmax
= { 0, 250 }, 0 },
671 { "rc_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcExpo8
, .config
.minmax
= { 0, 100 }, 0 },
672 { "rc_yaw_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcYawExpo8
, .config
.minmax
= { 0, 100 }, 0 },
673 { "thr_mid", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrMid8
, .config
.minmax
= { 0, 100 }, 0 },
674 { "thr_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrExpo8
, .config
.minmax
= { 0, 100 }, 0 },
675 { "roll_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_ROLL
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
}, 0 },
676 { "pitch_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_PITCH
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
}, 0 },
677 { "yaw_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_YAW
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX
}, 0 },
678 { "tpa_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].dynThrPID
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_TPA_MAX
}, 0 },
679 { "tpa_breakpoint", VAR_UINT16
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].tpa_breakpoint
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
}, 0 },
681 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_delay
, .config
.minmax
= { 0, 200 }, 0 },
682 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_off_delay
, .config
.minmax
= { 0, 200 }, 0 },
683 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
}, 0 },
684 { "failsafe_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
685 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
, .config
.minmax
= { 0, 300 }, 0 },
686 { "failsafe_procedure", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_procedure
, .config
.lookup
= { TABLE_FAILSAFE_PROCEDURE
}, 0 },
688 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_min_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, 0 },
689 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_max_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, 0 },
692 { "gimbal_mode", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].gimbalConfig
.mode
, .config
.lookup
= { TABLE_GIMBAL_MODE
}, 0 },
695 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.acc_hardware
, .config
.minmax
= { 0, ACC_MAX
}, 0 },
697 { "baro_tab_size", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_sample_count
, .config
.minmax
= { 0, BARO_SAMPLE_COUNT_MAX
}, 0 },
698 { "baro_noise_lpf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_noise_lpf
, .config
.minmax
= { 0, 1 }, 0 },
699 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.baro_hardware
, .config
.minmax
= { 0, BARO_MAX
}, 0 },
701 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.mag_hardware
, .config
.minmax
= { 0, MAG_MAX
}, 0 },
702 { "mag_declination", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].mag_declination
, .config
.minmax
= { -18000, 18000 }, 0 },
704 { "pid_controller", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.pidController
, .config
.lookup
= { TABLE_PID_CONTROLLER
}, 0 },
706 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
707 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
708 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
709 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
710 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
711 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
712 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
713 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
714 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
716 { "p_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[PITCH
], .config
.minmax
= { 0, 100 }, 0 },
717 { "i_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[PITCH
], .config
.minmax
= { 0, 100 }, 0 },
718 { "d_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[PITCH
], .config
.minmax
= { 0, 100 }, 0 },
719 { "p_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[ROLL
], .config
.minmax
= { 0, 100 }, 0 },
720 { "i_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[ROLL
], .config
.minmax
= { 0, 100 }, 0 },
721 { "d_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[ROLL
], .config
.minmax
= { 0, 100 }, 0 },
722 { "p_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[YAW
], .config
.minmax
= { 0, 100 }, 0 },
723 { "i_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[YAW
], .config
.minmax
= { 0, 100 }, 0 },
724 { "d_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[YAW
], .config
.minmax
= { 0, 100 }, 0 },
726 { "level_horizon", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.H_level
, .config
.minmax
= { 0, 10 }, 0 },
727 { "level_angle", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.A_level
, .config
.minmax
= { 0, 10 }, 0 },
728 { "sensitivity_horizon", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.H_sensitivity
, .config
.minmax
= { 0, 250 }, 0 },
730 { "p_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDLEVEL
], .config
.minmax
= { 0, 200 }, 0 },
731 { "i_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDLEVEL
], .config
.minmax
= { 0, 200 }, 0 },
732 { "d_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDLEVEL
], .config
.minmax
= { 0, 200 }, 0 },
734 { "yaw_p_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_p_limit
, .config
.minmax
= { YAW_P_LIMIT_MIN
, YAW_P_LIMIT_MAX
} },
735 { "gyro_soft_lpf", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.gyro_soft_lpf
, .config
.lookup
= { TABLE_SOFT_FILTER
}, 0 },
736 { "acc_soft_lpf", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.acc_soft_lpf
, .config
.lookup
= { TABLE_SOFT_FILTER
}, 0 },
737 { "dterm_cut_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_cut_hz
, .config
.minmax
= {0, 200 } },
738 { "yaw_pterm_cut_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_pterm_cut_hz
, .config
.minmax
= {0, 200 } },
741 { "gtune_loP_rll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_ROLL
], .config
.minmax
= { 10, 200 }, 0 },
742 { "gtune_loP_ptch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_PITCH
], .config
.minmax
= { 10, 200 }, 0 },
743 { "gtune_loP_yw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_YAW
], .config
.minmax
= { 10, 200 }, 0 },
744 { "gtune_hiP_rll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_ROLL
], .config
.minmax
= { 0, 200 }, 0 },
745 { "gtune_hiP_ptch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_PITCH
], .config
.minmax
= { 0, 200 }, 0 },
746 { "gtune_hiP_yw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_YAW
], .config
.minmax
= { 0, 200 }, 0 },
747 { "gtune_pwr", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_pwr
, .config
.minmax
= { 0, 10 }, 0 },
748 { "gtune_settle_time", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_settle_time
, .config
.minmax
= { 200, 1000 }, 0 },
749 { "gtune_average_cycles", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_average_cycles
, .config
.minmax
= { 8, 128 }, 0 },
753 { "blackbox_rate_num", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_num
, .config
.minmax
= { 1, 32 }, 0 },
754 { "blackbox_rate_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_denom
, .config
.minmax
= { 1, 32 }, 0 },
755 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.blackbox_device
, .config
.lookup
= { TABLE_BLACKBOX_DEVICE
}, 0 },
758 { "magzero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[X
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
759 { "magzero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Y
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
760 { "magzero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Z
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
762 { "acczero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[X
], .config
.minmax
= { -32768, 32767 }, 0 },
763 { "acczero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[Y
], .config
.minmax
= { -32768, 32767 }, 0 },
764 { "acczero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[Z
], .config
.minmax
= { -32768, 32767 }, 0 },
766 { "accgain_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[X
], .config
.minmax
= { 1, 8192 }, 0 },
767 { "accgain_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[Y
], .config
.minmax
= { 1, 8192 }, 0 },
768 { "accgain_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[Z
], .config
.minmax
= { 1, 8192 }, 0 },
771 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
779 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
);
780 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
);
781 static void cliPrint(const char *str
);
782 static void cliWrite(uint8_t ch
);
784 static void cliPrompt(void)
789 static void cliShowParseError(void)
791 cliPrint("Parse error\r\n");
794 static void cliShowArgumentRangeError(char *name
, int min
, int max
)
796 printf("%s must be between %d and %d\r\n", name
, min
, max
);
799 static char *processChannelRangeArgs(char *ptr
, channelRange_t
*range
, uint8_t *validArgumentCount
)
803 for (int argIndex
= 0; argIndex
< 2; argIndex
++) {
804 ptr
= strchr(ptr
, ' ');
807 val
= CHANNEL_VALUE_TO_STEP(val
);
808 if (val
>= MIN_MODE_RANGE_STEP
&& val
<= MAX_MODE_RANGE_STEP
) {
810 range
->startStep
= val
;
812 range
->endStep
= val
;
814 (*validArgumentCount
)++;
822 // Check if a string's length is zero
823 static bool isEmpty(const char *string
)
825 return *string
== '\0';
828 static void cliRxFail(char *cmdline
)
833 if (isEmpty(cmdline
)) {
834 // print out rxConfig failsafe settings
835 for (channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
836 cliRxFail(itoa(channel
, buf
, 10));
840 channel
= atoi(ptr
++);
841 if ((channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
)) {
843 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[channel
];
846 rxFailsafeChannelType_e type
= (channel
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_TYPE_FLIGHT
: RX_FAILSAFE_TYPE_AUX
;
847 rxFailsafeChannelMode_e mode
= channelFailsafeConfiguration
->mode
;
848 bool requireValue
= channelFailsafeConfiguration
->mode
== RX_FAILSAFE_MODE_SET
;
850 ptr
= strchr(ptr
, ' ');
852 char *p
= strchr(rxFailsafeModeCharacters
, *(++ptr
));
854 uint8_t requestedMode
= p
- rxFailsafeModeCharacters
;
855 mode
= rxFailsafeModesTable
[type
][requestedMode
];
857 mode
= RX_FAILSAFE_MODE_INVALID
;
859 if (mode
== RX_FAILSAFE_MODE_INVALID
) {
864 requireValue
= mode
== RX_FAILSAFE_MODE_SET
;
866 ptr
= strchr(ptr
, ' ');
873 value
= CHANNEL_VALUE_TO_RXFAIL_STEP(value
);
874 if (value
> MAX_RXFAIL_RANGE_STEP
) {
875 cliPrint("Value out of range\r\n");
879 channelFailsafeConfiguration
->step
= value
;
880 } else if (requireValue
) {
884 channelFailsafeConfiguration
->mode
= mode
;
888 char modeCharacter
= rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
];
890 // triple use of printf below
891 // 1. acknowledge interpretation on command,
892 // 2. query current setting on single item,
893 // 3. recursive use for full list.
896 printf("rxfail %u %c %d\r\n",
899 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration
->step
)
902 printf("rxfail %u %c\r\n",
908 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
- 1);
913 static void cliAux(char *cmdline
)
918 if (isEmpty(cmdline
)) {
919 // print out aux channel settings
920 for (i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
921 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
922 printf("aux %u %u %u %u %u\r\n",
925 mac
->auxChannelIndex
,
926 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
927 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
)
933 if (i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
) {
934 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
935 uint8_t validArgumentCount
= 0;
936 ptr
= strchr(ptr
, ' ');
939 if (val
>= 0 && val
< CHECKBOX_ITEM_COUNT
) {
941 validArgumentCount
++;
944 ptr
= strchr(ptr
, ' ');
947 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
948 mac
->auxChannelIndex
= val
;
949 validArgumentCount
++;
952 ptr
= processChannelRangeArgs(ptr
, &mac
->range
, &validArgumentCount
);
954 if (validArgumentCount
!= 4) {
955 memset(mac
, 0, sizeof(modeActivationCondition_t
));
958 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT
- 1);
963 static void cliSerial(char *cmdline
)
968 if (isEmpty(cmdline
)) {
969 for (i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
970 if (!serialIsPortAvailable(masterConfig
.serialConfig
.portConfigs
[i
].identifier
)) {
973 printf("serial %d %d %ld %ld %ld %ld\r\n" ,
974 masterConfig
.serialConfig
.portConfigs
[i
].identifier
,
975 masterConfig
.serialConfig
.portConfigs
[i
].functionMask
,
976 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].msp_baudrateIndex
],
977 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].gps_baudrateIndex
],
978 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].telemetry_baudrateIndex
],
979 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].blackbox_baudrateIndex
]
985 serialPortConfig_t portConfig
;
986 memset(&portConfig
, 0 , sizeof(portConfig
));
988 serialPortConfig_t
*currentConfig
;
990 uint8_t validArgumentCount
= 0;
995 currentConfig
= serialFindPortConfiguration(val
);
997 portConfig
.identifier
= val
;
998 validArgumentCount
++;
1001 ptr
= strchr(ptr
, ' ');
1004 portConfig
.functionMask
= val
& 0xFFFF;
1005 validArgumentCount
++;
1008 for (i
= 0; i
< 4; i
++) {
1009 ptr
= strchr(ptr
, ' ');
1016 uint8_t baudRateIndex
= lookupBaudRateIndex(val
);
1017 if (baudRates
[baudRateIndex
] != (uint32_t) val
) {
1023 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1026 portConfig
.msp_baudrateIndex
= baudRateIndex
;
1029 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1032 portConfig
.gps_baudrateIndex
= baudRateIndex
;
1035 if (baudRateIndex
!= BAUD_AUTO
&& baudRateIndex
> BAUD_115200
) {
1038 portConfig
.telemetry_baudrateIndex
= baudRateIndex
;
1041 if (baudRateIndex
< BAUD_19200
|| baudRateIndex
> BAUD_250000
) {
1044 portConfig
.blackbox_baudrateIndex
= baudRateIndex
;
1048 validArgumentCount
++;
1051 if (validArgumentCount
< 6) {
1052 cliShowParseError();
1056 memcpy(currentConfig
, &portConfig
, sizeof(portConfig
));
1060 static void cliAdjustmentRange(char *cmdline
)
1065 if (isEmpty(cmdline
)) {
1066 // print out adjustment ranges channel settings
1067 for (i
= 0; i
< MAX_ADJUSTMENT_RANGE_COUNT
; i
++) {
1068 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
1069 printf("adjrange %u %u %u %u %u %u %u\r\n",
1071 ar
->adjustmentIndex
,
1072 ar
->auxChannelIndex
,
1073 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
1074 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
1075 ar
->adjustmentFunction
,
1076 ar
->auxSwitchChannelIndex
1082 if (i
< MAX_ADJUSTMENT_RANGE_COUNT
) {
1083 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
1084 uint8_t validArgumentCount
= 0;
1086 ptr
= strchr(ptr
, ' ');
1089 if (val
>= 0 && val
< MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
) {
1090 ar
->adjustmentIndex
= val
;
1091 validArgumentCount
++;
1094 ptr
= strchr(ptr
, ' ');
1097 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1098 ar
->auxChannelIndex
= val
;
1099 validArgumentCount
++;
1103 ptr
= processChannelRangeArgs(ptr
, &ar
->range
, &validArgumentCount
);
1105 ptr
= strchr(ptr
, ' ');
1108 if (val
>= 0 && val
< ADJUSTMENT_FUNCTION_COUNT
) {
1109 ar
->adjustmentFunction
= val
;
1110 validArgumentCount
++;
1113 ptr
= strchr(ptr
, ' ');
1116 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1117 ar
->auxSwitchChannelIndex
= val
;
1118 validArgumentCount
++;
1122 if (validArgumentCount
!= 6) {
1123 memset(ar
, 0, sizeof(adjustmentRange_t
));
1124 cliShowParseError();
1127 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT
- 1);
1132 static void cliMotorMix(char *cmdline
)
1134 #ifdef USE_QUAD_MIXER_ONLY
1143 if (isEmpty(cmdline
)) {
1144 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1145 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1146 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1149 printf("#%d:\t", i
);
1150 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].throttle
, buf
));
1151 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].roll
, buf
));
1152 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].pitch
, buf
));
1153 printf("%s\r\n", ftoa(masterConfig
.customMotorMixer
[i
].yaw
, buf
));
1156 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1157 // erase custom mixer
1158 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
1159 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
1160 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1161 ptr
= strchr(cmdline
, ' ');
1163 len
= strlen(++ptr
);
1164 for (i
= 0; ; i
++) {
1165 if (mixerNames
[i
] == NULL
) {
1166 cliPrint("Invalid name\r\n");
1169 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1170 mixerLoadMix(i
, masterConfig
.customMotorMixer
);
1171 printf("Loaded %s\r\n", mixerNames
[i
]);
1179 i
= atoi(ptr
); // get motor number
1180 if (i
< MAX_SUPPORTED_MOTORS
) {
1181 ptr
= strchr(ptr
, ' ');
1183 masterConfig
.customMotorMixer
[i
].throttle
= fastA2F(++ptr
);
1186 ptr
= strchr(ptr
, ' ');
1188 masterConfig
.customMotorMixer
[i
].roll
= fastA2F(++ptr
);
1191 ptr
= strchr(ptr
, ' ');
1193 masterConfig
.customMotorMixer
[i
].pitch
= fastA2F(++ptr
);
1196 ptr
= strchr(ptr
, ' ');
1198 masterConfig
.customMotorMixer
[i
].yaw
= fastA2F(++ptr
);
1202 cliShowParseError();
1207 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
1213 static void cliRxRange(char *cmdline
)
1215 int i
, validArgumentCount
= 0;
1218 if (isEmpty(cmdline
)) {
1219 for (i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
1220 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1221 printf("rxrange %u %u %u\r\n", i
, channelRangeConfiguration
->min
, channelRangeConfiguration
->max
);
1223 } else if (strcasecmp(cmdline
, "reset") == 0) {
1224 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
1228 if (i
>= 0 && i
< NON_AUX_CHANNEL_COUNT
) {
1229 int rangeMin
, rangeMax
;
1231 ptr
= strchr(ptr
, ' ');
1233 rangeMin
= atoi(++ptr
);
1234 validArgumentCount
++;
1237 ptr
= strchr(ptr
, ' ');
1239 rangeMax
= atoi(++ptr
);
1240 validArgumentCount
++;
1243 if (validArgumentCount
!= 2) {
1244 cliShowParseError();
1245 } else if (rangeMin
< PWM_PULSE_MIN
|| rangeMin
> PWM_PULSE_MAX
|| rangeMax
< PWM_PULSE_MIN
|| rangeMax
> PWM_PULSE_MAX
) {
1246 cliShowParseError();
1248 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1249 channelRangeConfiguration
->min
= rangeMin
;
1250 channelRangeConfiguration
->max
= rangeMax
;
1253 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT
- 1);
1259 static void cliLed(char *cmdline
)
1263 char ledConfigBuffer
[20];
1265 if (isEmpty(cmdline
)) {
1266 for (i
= 0; i
< MAX_LED_STRIP_LENGTH
; i
++) {
1267 generateLedConfig(i
, ledConfigBuffer
, sizeof(ledConfigBuffer
));
1268 printf("led %u %s\r\n", i
, ledConfigBuffer
);
1273 if (i
< MAX_LED_STRIP_LENGTH
) {
1274 ptr
= strchr(cmdline
, ' ');
1275 if (!parseLedStripConfig(i
, ++ptr
)) {
1276 cliShowParseError();
1279 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH
- 1);
1284 static void cliColor(char *cmdline
)
1289 if (isEmpty(cmdline
)) {
1290 for (i
= 0; i
< CONFIGURABLE_COLOR_COUNT
; i
++) {
1291 printf("color %u %d,%u,%u\r\n",
1293 masterConfig
.colors
[i
].h
,
1294 masterConfig
.colors
[i
].s
,
1295 masterConfig
.colors
[i
].v
1301 if (i
< CONFIGURABLE_COLOR_COUNT
) {
1302 ptr
= strchr(cmdline
, ' ');
1303 if (!parseColor(i
, ++ptr
)) {
1304 cliShowParseError();
1307 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT
- 1);
1314 static void cliServo(char *cmdline
)
1316 enum { SERVO_ARGUMENT_COUNT
= 8 };
1317 int16_t arguments
[SERVO_ARGUMENT_COUNT
];
1319 servoParam_t
*servo
;
1324 if (isEmpty(cmdline
)) {
1325 // print out servo settings
1326 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1327 servo
= ¤tProfile
->servoConf
[i
];
1329 printf("servo %u %d %d %d %d %d %d %d\r\n",
1337 servo
->forwardFromChannel
1341 int validArgumentCount
= 0;
1345 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1347 // If command line doesn't fit the format, don't modify the config
1349 if (*ptr
== '-' || (*ptr
>= '0' && *ptr
<= '9')) {
1350 if (validArgumentCount
>= SERVO_ARGUMENT_COUNT
) {
1351 cliShowParseError();
1355 arguments
[validArgumentCount
++] = atoi(ptr
);
1359 } while (*ptr
>= '0' && *ptr
<= '9');
1360 } else if (*ptr
== ' ') {
1363 cliShowParseError();
1368 enum {INDEX
= 0, MIN
, MAX
, MIDDLE
, ANGLE_AT_MIN
, ANGLE_AT_MAX
, RATE
, FORWARD
};
1370 i
= arguments
[INDEX
];
1372 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1373 if (validArgumentCount
!= SERVO_ARGUMENT_COUNT
|| i
< 0 || i
>= MAX_SUPPORTED_SERVOS
) {
1374 cliShowParseError();
1378 servo
= ¤tProfile
->servoConf
[i
];
1381 arguments
[MIN
] < PWM_PULSE_MIN
|| arguments
[MIN
] > PWM_PULSE_MAX
||
1382 arguments
[MAX
] < PWM_PULSE_MIN
|| arguments
[MAX
] > PWM_PULSE_MAX
||
1383 arguments
[MIDDLE
] < arguments
[MIN
] || arguments
[MIDDLE
] > arguments
[MAX
] ||
1384 arguments
[MIN
] > arguments
[MAX
] || arguments
[MAX
] < arguments
[MIN
] ||
1385 arguments
[RATE
] < -100 || arguments
[RATE
] > 100 ||
1386 arguments
[FORWARD
] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
||
1387 arguments
[ANGLE_AT_MIN
] < 0 || arguments
[ANGLE_AT_MIN
] > 180 ||
1388 arguments
[ANGLE_AT_MAX
] < 0 || arguments
[ANGLE_AT_MAX
] > 180
1390 cliShowParseError();
1394 servo
->min
= arguments
[1];
1395 servo
->max
= arguments
[2];
1396 servo
->middle
= arguments
[3];
1397 servo
->angleAtMin
= arguments
[4];
1398 servo
->angleAtMax
= arguments
[5];
1399 servo
->rate
= arguments
[6];
1400 servo
->forwardFromChannel
= arguments
[7];
1406 static void cliServoMix(char *cmdline
)
1411 int args
[8], check
= 0;
1412 len
= strlen(cmdline
);
1416 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1418 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1419 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1422 printf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1424 masterConfig
.customServoMixer
[i
].targetChannel
,
1425 masterConfig
.customServoMixer
[i
].inputSource
,
1426 masterConfig
.customServoMixer
[i
].rate
,
1427 masterConfig
.customServoMixer
[i
].speed
,
1428 masterConfig
.customServoMixer
[i
].min
,
1429 masterConfig
.customServoMixer
[i
].max
,
1430 masterConfig
.customServoMixer
[i
].box
1435 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1436 // erase custom mixer
1437 memset(masterConfig
.customServoMixer
, 0, sizeof(masterConfig
.customServoMixer
));
1438 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1439 currentProfile
->servoConf
[i
].reversedSources
= 0;
1441 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1442 ptr
= strchr(cmdline
, ' ');
1444 len
= strlen(++ptr
);
1445 for (i
= 0; ; i
++) {
1446 if (mixerNames
[i
] == NULL
) {
1447 printf("Invalid name\r\n");
1450 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1451 servoMixerLoadMix(i
, masterConfig
.customServoMixer
);
1452 printf("Loaded %s\r\n", mixerNames
[i
]);
1458 } else if (strncasecmp(cmdline
, "reverse", 7) == 0) {
1459 enum {SERVO
= 0, INPUT
, REVERSE
, ARGS_COUNT
};
1460 int servoIndex
, inputSource
;
1461 ptr
= strchr(cmdline
, ' ');
1466 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1467 printf("\ti%d", inputSource
);
1470 for (servoIndex
= 0; servoIndex
< MAX_SUPPORTED_SERVOS
; servoIndex
++) {
1471 printf("%d", servoIndex
);
1472 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1473 printf("\t%s ", (currentProfile
->servoConf
[servoIndex
].reversedSources
& (1 << inputSource
)) ? "r" : "n");
1479 ptr
= strtok(ptr
, " ");
1480 while (ptr
!= NULL
&& check
< ARGS_COUNT
- 1) {
1481 args
[check
++] = atoi(ptr
);
1482 ptr
= strtok(NULL
, " ");
1485 if (ptr
== NULL
|| check
!= ARGS_COUNT
- 1) {
1486 cliShowParseError();
1490 if (args
[SERVO
] >= 0 && args
[SERVO
] < MAX_SUPPORTED_SERVOS
1491 && args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
1492 && (*ptr
== 'r' || *ptr
== 'n')) {
1494 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
|= 1 << args
[INPUT
];
1496 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
&= ~(1 << args
[INPUT
]);
1498 cliShowParseError();
1500 cliServoMix("reverse");
1502 enum {RULE
= 0, TARGET
, INPUT
, RATE
, SPEED
, MIN
, MAX
, BOX
, ARGS_COUNT
};
1503 ptr
= strtok(cmdline
, " ");
1504 while (ptr
!= NULL
&& check
< ARGS_COUNT
) {
1505 args
[check
++] = atoi(ptr
);
1506 ptr
= strtok(NULL
, " ");
1509 if (ptr
!= NULL
|| check
!= ARGS_COUNT
) {
1510 cliShowParseError();
1515 if (i
>= 0 && i
< MAX_SERVO_RULES
&&
1516 args
[TARGET
] >= 0 && args
[TARGET
] < MAX_SUPPORTED_SERVOS
&&
1517 args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
&&
1518 args
[RATE
] >= -100 && args
[RATE
] <= 100 &&
1519 args
[SPEED
] >= 0 && args
[SPEED
] <= MAX_SERVO_SPEED
&&
1520 args
[MIN
] >= 0 && args
[MIN
] <= 100 &&
1521 args
[MAX
] >= 0 && args
[MAX
] <= 100 && args
[MIN
] < args
[MAX
] &&
1522 args
[BOX
] >= 0 && args
[BOX
] <= MAX_SERVO_BOXES
) {
1523 masterConfig
.customServoMixer
[i
].targetChannel
= args
[TARGET
];
1524 masterConfig
.customServoMixer
[i
].inputSource
= args
[INPUT
];
1525 masterConfig
.customServoMixer
[i
].rate
= args
[RATE
];
1526 masterConfig
.customServoMixer
[i
].speed
= args
[SPEED
];
1527 masterConfig
.customServoMixer
[i
].min
= args
[MIN
];
1528 masterConfig
.customServoMixer
[i
].max
= args
[MAX
];
1529 masterConfig
.customServoMixer
[i
].box
= args
[BOX
];
1532 cliShowParseError();
1541 static void cliFlashInfo(char *cmdline
)
1543 const flashGeometry_t
*layout
= flashfsGetGeometry();
1547 printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1548 layout
->sectors
, layout
->sectorSize
, layout
->pagesPerSector
, layout
->pageSize
, layout
->totalSize
, flashfsGetOffset());
1551 static void cliFlashErase(char *cmdline
)
1555 printf("Erasing...\r\n");
1556 flashfsEraseCompletely();
1558 while (!flashfsIsReady()) {
1562 printf("Done.\r\n");
1565 #ifdef USE_FLASH_TOOLS
1567 static void cliFlashWrite(char *cmdline
)
1569 uint32_t address
= atoi(cmdline
);
1570 char *text
= strchr(cmdline
, ' ');
1573 cliShowParseError();
1575 flashfsSeekAbs(address
);
1576 flashfsWrite((uint8_t*)text
, strlen(text
), true);
1579 printf("Wrote %u bytes at %u.\r\n", strlen(text
), address
);
1583 static void cliFlashRead(char *cmdline
)
1585 uint32_t address
= atoi(cmdline
);
1591 char *nextArg
= strchr(cmdline
, ' ');
1594 cliShowParseError();
1596 length
= atoi(nextArg
);
1598 printf("Reading %u bytes at %u:\r\n", length
, address
);
1600 while (length
> 0) {
1603 bytesRead
= flashfsReadAbs(address
, buffer
, length
< sizeof(buffer
) ? length
: sizeof(buffer
));
1605 for (i
= 0; i
< bytesRead
; i
++) {
1606 cliWrite(buffer
[i
]);
1609 length
-= bytesRead
;
1610 address
+= bytesRead
;
1612 if (bytesRead
== 0) {
1613 //Assume we reached the end of the volume or something fatal happened
1624 static void dumpValues(uint16_t valueSection
)
1627 const clivalue_t
*value
;
1628 for (i
= 0; i
< VALUE_COUNT
; i
++) {
1629 value
= &valueTable
[i
];
1631 if ((value
->type
& VALUE_SECTION_MASK
) != valueSection
) {
1635 printf("set %s = ", valueTable
[i
].name
);
1636 cliPrintVar(value
, 0);
1642 DUMP_MASTER
= (1 << 0),
1643 DUMP_PROFILE
= (1 << 1),
1644 DUMP_CONTROL_RATE_PROFILE
= (1 << 2)
1647 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
1650 static const char* const sectionBreak
= "\r\n";
1652 #define printSectionBreak() printf((char *)sectionBreak)
1654 static void cliDump(char *cmdline
)
1660 #ifndef USE_QUAD_MIXER_ONLY
1661 float thr
, roll
, pitch
, yaw
;
1664 uint8_t dumpMask
= DUMP_ALL
;
1665 if (strcasecmp(cmdline
, "master") == 0) {
1666 dumpMask
= DUMP_MASTER
; // only
1668 if (strcasecmp(cmdline
, "profile") == 0) {
1669 dumpMask
= DUMP_PROFILE
; // only
1671 if (strcasecmp(cmdline
, "rates") == 0) {
1672 dumpMask
= DUMP_CONTROL_RATE_PROFILE
; // only
1675 if (dumpMask
& DUMP_MASTER
) {
1677 cliPrint("\r\n# version\r\n");
1680 cliPrint("\r\n# pflags\r\n");
1683 cliPrint("\r\n# dump master\r\n");
1684 cliPrint("\r\n# mixer\r\n");
1686 #ifndef USE_QUAD_MIXER_ONLY
1687 printf("mixer %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
1689 printf("mmix reset\r\n");
1691 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1692 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1694 thr
= masterConfig
.customMotorMixer
[i
].throttle
;
1695 roll
= masterConfig
.customMotorMixer
[i
].roll
;
1696 pitch
= masterConfig
.customMotorMixer
[i
].pitch
;
1697 yaw
= masterConfig
.customMotorMixer
[i
].yaw
;
1698 printf("mmix %d", i
);
1701 printf("%s", ftoa(thr
, buf
));
1704 printf("%s", ftoa(roll
, buf
));
1707 printf("%s", ftoa(pitch
, buf
));
1710 printf("%s\r\n", ftoa(yaw
, buf
));
1713 // print custom servo mixer if exists
1714 printf("smix reset\r\n");
1716 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1718 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1721 printf("smix %d %d %d %d %d %d %d %d\r\n",
1723 masterConfig
.customServoMixer
[i
].targetChannel
,
1724 masterConfig
.customServoMixer
[i
].inputSource
,
1725 masterConfig
.customServoMixer
[i
].rate
,
1726 masterConfig
.customServoMixer
[i
].speed
,
1727 masterConfig
.customServoMixer
[i
].min
,
1728 masterConfig
.customServoMixer
[i
].max
,
1729 masterConfig
.customServoMixer
[i
].box
1736 cliPrint("\r\n\r\n# feature\r\n");
1738 mask
= featureMask();
1739 for (i
= 0; ; i
++) { // disable all feature first
1740 if (featureNames
[i
] == NULL
)
1742 printf("feature -%s\r\n", featureNames
[i
]);
1744 for (i
= 0; ; i
++) { // reenable what we want.
1745 if (featureNames
[i
] == NULL
)
1747 if (mask
& (1 << i
))
1748 printf("feature %s\r\n", featureNames
[i
]);
1751 cliPrint("\r\n\r\n# map\r\n");
1753 for (i
= 0; i
< 8; i
++)
1754 buf
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
1756 printf("map %s\r\n", buf
);
1758 cliPrint("\r\n\r\n# serial\r\n");
1762 cliPrint("\r\n\r\n# led\r\n");
1765 cliPrint("\r\n\r\n# color\r\n");
1768 printSectionBreak();
1769 dumpValues(MASTER_VALUE
);
1771 cliPrint("\r\n# rxfail\r\n");
1775 if (dumpMask
& DUMP_PROFILE
) {
1776 cliPrint("\r\n# dump profile\r\n");
1778 cliPrint("\r\n# profile\r\n");
1781 cliPrint("\r\n# aux\r\n");
1785 cliPrint("\r\n# adjrange\r\n");
1787 cliAdjustmentRange("");
1789 printf("\r\n# rxrange\r\n");
1794 cliPrint("\r\n# servo\r\n");
1798 // print servo directions
1799 unsigned int channel
;
1801 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1802 for (channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
1803 if (servoDirection(i
, channel
) < 0) {
1804 printf("smix reverse %d %d r\r\n", i
, channel
);
1810 printSectionBreak();
1812 dumpValues(PROFILE_VALUE
);
1815 if (dumpMask
& DUMP_CONTROL_RATE_PROFILE
) {
1816 cliPrint("\r\n# dump rates\r\n");
1818 cliPrint("\r\n# rateprofile\r\n");
1821 printSectionBreak();
1823 dumpValues(CONTROL_RATE_VALUE
);
1827 void cliEnter(serialPort_t
*serialPort
)
1830 cliPort
= serialPort
;
1831 setPrintfSerialPort(cliPort
);
1832 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1834 ENABLE_ARMING_FLAG(PREVENT_ARMING
);
1837 static void cliExit(char *cmdline
)
1841 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1845 // incase a motor was left running during motortest, clear it here
1846 mixerResetDisarmedMotors();
1852 static void cliFeature(char *cmdline
)
1858 len
= strlen(cmdline
);
1859 mask
= featureMask();
1862 cliPrint("Enabled: ");
1863 for (i
= 0; ; i
++) {
1864 if (featureNames
[i
] == NULL
)
1866 if (mask
& (1 << i
))
1867 printf("%s ", featureNames
[i
]);
1870 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
1871 cliPrint("Available: ");
1872 for (i
= 0; ; i
++) {
1873 if (featureNames
[i
] == NULL
)
1875 printf("%s ", featureNames
[i
]);
1880 bool remove
= false;
1881 if (cmdline
[0] == '-') {
1884 cmdline
++; // skip over -
1888 for (i
= 0; ; i
++) {
1889 if (featureNames
[i
] == NULL
) {
1890 cliPrint("Invalid name\r\n");
1894 if (strncasecmp(cmdline
, featureNames
[i
], len
) == 0) {
1898 if (mask
& FEATURE_GPS
) {
1899 cliPrint("unavailable\r\n");
1904 if (mask
& FEATURE_SONAR
) {
1905 cliPrint("unavailable\r\n");
1911 cliPrint("Disabled");
1914 cliPrint("Enabled");
1916 printf(" %s\r\n", featureNames
[i
]);
1924 static void cliGpsPassthrough(char *cmdline
)
1928 gpsEnablePassthrough(cliPort
);
1932 static void cliHelp(char *cmdline
)
1938 for (i
= 0; i
< CMD_COUNT
; i
++) {
1939 cliPrint(cmdTable
[i
].name
);
1940 #ifndef SKIP_CLI_COMMAND_HELP
1941 if (cmdTable
[i
].description
) {
1942 printf(" - %s", cmdTable
[i
].description
);
1944 if (cmdTable
[i
].args
) {
1945 printf("\r\n\t%s", cmdTable
[i
].args
);
1952 static void cliMap(char *cmdline
)
1958 len
= strlen(cmdline
);
1962 for (i
= 0; i
< 8; i
++)
1963 cmdline
[i
] = toupper((unsigned char)cmdline
[i
]);
1964 for (i
= 0; i
< 8; i
++) {
1965 if (strchr(rcChannelLetters
, cmdline
[i
]) && !strchr(cmdline
+ i
+ 1, cmdline
[i
]))
1967 cliShowParseError();
1970 parseRcChannels(cmdline
, &masterConfig
.rxConfig
);
1973 for (i
= 0; i
< 8; i
++)
1974 out
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
1976 printf("%s\r\n", out
);
1979 #ifndef USE_QUAD_MIXER_ONLY
1980 static void cliMixer(char *cmdline
)
1985 len
= strlen(cmdline
);
1988 printf("Mixer: %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
1990 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
1991 cliPrint("Available mixers: ");
1992 for (i
= 0; ; i
++) {
1993 if (mixerNames
[i
] == NULL
)
1995 printf("%s ", mixerNames
[i
]);
2001 for (i
= 0; ; i
++) {
2002 if (mixerNames
[i
] == NULL
) {
2003 cliPrint("Invalid name\r\n");
2006 if (strncasecmp(cmdline
, mixerNames
[i
], len
) == 0) {
2007 masterConfig
.mixerMode
= i
+ 1;
2016 static void cliMotor(char *cmdline
)
2018 int motor_index
= 0;
2019 int motor_value
= 0;
2024 if (isEmpty(cmdline
)) {
2025 cliShowParseError();
2029 pch
= strtok_r(cmdline
, " ", &saveptr
);
2030 while (pch
!= NULL
) {
2033 motor_index
= atoi(pch
);
2036 motor_value
= atoi(pch
);
2040 pch
= strtok_r(NULL
, " ", &saveptr
);
2043 if (motor_index
< 0 || motor_index
>= MAX_SUPPORTED_MOTORS
) {
2044 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
2049 if (motor_value
< PWM_RANGE_MIN
|| motor_value
> PWM_RANGE_MAX
) {
2050 cliShowArgumentRangeError("value", 1000, 2000);
2053 motor_disarmed
[motor_index
] = motor_value
;
2057 printf("motor %d: %d\r\n", motor_index
, motor_disarmed
[motor_index
]);
2060 static void cliPlaySound(char *cmdline
)
2062 #if FLASH_SIZE <= 64
2067 static int lastSoundIdx
= -1;
2069 if (isEmpty(cmdline
)) {
2070 i
= lastSoundIdx
+ 1; //next sound index
2071 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
2072 while (true) { //no name for index; try next one
2073 if (++i
>= beeperTableEntryCount())
2074 i
= 0; //if end then wrap around to first entry
2075 if ((name
=beeperNameForTableIndex(i
)) != NULL
)
2076 break; //if name OK then play sound below
2077 if (i
== lastSoundIdx
+ 1) { //prevent infinite loop
2078 printf("Error playing sound\r\n");
2083 } else { //index value was given
2085 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
2086 printf("No sound for index %d\r\n", i
);
2092 printf("Playing sound %d: %s\r\n", i
, name
);
2093 beeper(beeperModeForTableIndex(i
));
2097 static void cliProfile(char *cmdline
)
2101 if (isEmpty(cmdline
)) {
2102 printf("profile %d\r\n", getCurrentProfile());
2106 if (i
>= 0 && i
< MAX_PROFILE_COUNT
) {
2107 masterConfig
.current_profile_index
= i
;
2115 static void cliRateProfile(char *cmdline
)
2119 if (isEmpty(cmdline
)) {
2120 printf("rateprofile %d\r\n", getCurrentControlRateProfile());
2124 if (i
>= 0 && i
< MAX_CONTROL_RATE_PROFILE_COUNT
) {
2125 changeControlRateProfile(i
);
2131 static void cliReboot(void) {
2132 cliPrint("\r\nRebooting");
2133 waitForSerialPortToFinishTransmitting(cliPort
);
2135 handleOneshotFeatureChangeOnRestart();
2139 static void cliSave(char *cmdline
)
2144 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2149 static void cliDefaults(char *cmdline
)
2153 cliPrint("Resetting to defaults");
2158 static void cliPrint(const char *str
)
2161 serialWrite(cliPort
, *(str
++));
2164 static void cliWrite(uint8_t ch
)
2166 serialWrite(cliPort
, ch
);
2169 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
)
2174 void *ptr
= var
->ptr
;
2175 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
2176 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
2178 if ((var
->type
& VALUE_SECTION_MASK
) == CONTROL_RATE_VALUE
) {
2179 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
2182 switch (var
->type
& VALUE_TYPE_MASK
) {
2184 value
= *(uint8_t *)ptr
;
2188 value
= *(int8_t *)ptr
;
2192 value
= *(uint16_t *)ptr
;
2196 value
= *(int16_t *)ptr
;
2200 value
= *(uint32_t *)ptr
;
2204 printf("%s", ftoa(*(float *)ptr
, buf
));
2205 if (full
&& (var
->type
& VALUE_MODE_MASK
) == MODE_DIRECT
) {
2206 printf(" %s", ftoa((float)var
->config
.minmax
.min
, buf
));
2207 printf(" %s", ftoa((float)var
->config
.minmax
.max
, buf
));
2209 return; // return from case for float only
2212 switch(var
->type
& VALUE_MODE_MASK
) {
2214 printf("%d", value
);
2216 printf(" %d %d", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
2220 printf(lookupTables
[var
->config
.lookup
.tableIndex
].values
[value
]);
2225 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
)
2227 void *ptr
= var
->ptr
;
2228 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
2229 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
2231 if ((var
->type
& VALUE_SECTION_MASK
) == CONTROL_RATE_VALUE
) {
2232 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
2235 switch (var
->type
& VALUE_TYPE_MASK
) {
2238 *(int8_t *)ptr
= value
.int_value
;
2243 *(int16_t *)ptr
= value
.int_value
;
2247 *(uint32_t *)ptr
= value
.int_value
;
2251 *(float *)ptr
= (float)value
.float_value
;
2255 if (var
->pflags_to_set
) {
2256 persistentFlagSet(var
->pflags_to_set
);
2260 static void cliSet(char *cmdline
)
2264 const clivalue_t
*val
;
2267 len
= strlen(cmdline
);
2269 if (len
== 0 || (len
== 1 && cmdline
[0] == '*')) {
2270 cliPrint("Current settings: \r\n");
2271 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2272 val
= &valueTable
[i
];
2273 printf("%s = ", valueTable
[i
].name
);
2274 cliPrintVar(val
, len
); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2277 } else if ((eqptr
= strstr(cmdline
, "=")) != NULL
) {
2280 char *lastNonSpaceCharacter
= eqptr
;
2281 while (*(lastNonSpaceCharacter
- 1) == ' ') {
2282 lastNonSpaceCharacter
--;
2284 uint8_t variableNameLength
= lastNonSpaceCharacter
- cmdline
;
2286 // skip the '=' and any ' ' characters
2288 while (*(eqptr
) == ' ') {
2292 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2293 val
= &valueTable
[i
];
2294 // ensure exact match when setting to prevent setting variables with shorter names
2295 if (strncasecmp(cmdline
, valueTable
[i
].name
, strlen(valueTable
[i
].name
)) == 0 && variableNameLength
== strlen(valueTable
[i
].name
)) {
2297 bool changeValue
= false;
2298 int_float_value_t tmp
;
2299 switch (valueTable
[i
].type
& VALUE_MODE_MASK
) {
2304 value
= atoi(eqptr
);
2305 valuef
= fastA2F(eqptr
);
2307 if (valuef
>= valueTable
[i
].config
.minmax
.min
&& valuef
<= valueTable
[i
].config
.minmax
.max
) { // note: compare float value
2309 if ((valueTable
[i
].type
& VALUE_TYPE_MASK
) == VAR_FLOAT
)
2310 tmp
.float_value
= valuef
;
2312 tmp
.int_value
= value
;
2319 const lookupTableEntry_t
*tableEntry
= &lookupTables
[valueTable
[i
].config
.lookup
.tableIndex
];
2320 bool matched
= false;
2321 for (uint8_t tableValueIndex
= 0; tableValueIndex
< tableEntry
->valueCount
&& !matched
; tableValueIndex
++) {
2322 matched
= strcasecmp(tableEntry
->values
[tableValueIndex
], eqptr
) == 0;
2325 tmp
.int_value
= tableValueIndex
;
2334 cliSetVar(val
, tmp
);
2336 printf("%s set to ", valueTable
[i
].name
);
2337 cliPrintVar(val
, 0);
2339 cliPrint("Invalid value\r\n");
2345 cliPrint("Invalid name\r\n");
2347 // no equals, check for matching variables.
2352 static void cliGet(char *cmdline
)
2355 const clivalue_t
*val
;
2356 int matchedCommands
= 0;
2358 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2359 if (strstr(valueTable
[i
].name
, cmdline
)) {
2360 val
= &valueTable
[i
];
2361 printf("%s = ", valueTable
[i
].name
);
2362 cliPrintVar(val
, 0);
2370 if (matchedCommands
) {
2374 cliPrint("Invalid name\r\n");
2377 static void cliStatus(char *cmdline
)
2381 printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), System load: %d.%02d\r\n",
2382 millis() / 1000, vbat
, batteryCellCount
, getBatteryStateString(), averageSystemLoadPercent
/ 100, averageSystemLoadPercent
% 100);
2384 printf("CPU Clock=%dMHz", (SystemCoreClock
/ 1000000));
2389 uint32_t detectedSensorsMask
= sensorsMask();
2391 for (i
= 0; ; i
++) {
2393 if (sensorTypeNames
[i
] == NULL
)
2397 if ((detectedSensorsMask
& mask
) && (mask
& SENSOR_NAMES_MASK
)) {
2398 const char *sensorHardware
;
2399 uint8_t sensorHardwareIndex
= detectedSensors
[i
];
2400 sensorHardware
= sensorHardwareNames
[i
][sensorHardwareIndex
];
2402 printf(", %s=%s", sensorTypeNames
[i
], sensorHardware
);
2404 if (mask
== SENSOR_ACC
&& acc
.revisionCode
) {
2405 printf(".%c", acc
.revisionCode
);
2413 uint16_t i2cErrorCounter
= i2cGetErrorCounter();
2415 uint16_t i2cErrorCounter
= 0;
2418 printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime
, i2cErrorCounter
, sizeof(master_t
));
2421 #ifndef SKIP_TASK_STATISTICS
2422 static void cliTasks(char *cmdline
)
2427 cfTaskInfo_t taskInfo
;
2429 printf("Task list:\r\n");
2430 for (taskId
= 0; taskId
< TASK_COUNT
; taskId
++) {
2431 getTaskInfo(taskId
, &taskInfo
);
2432 if (taskInfo
.isEnabled
) {
2433 printf("%d - %s, max = %d us, avg = %d us, total = %d ms\r\n", taskId
, taskInfo
.taskName
, taskInfo
.maxExecutionTime
, taskInfo
.averageExecutionTime
, taskInfo
.totalExecutionTime
/ 1000);
2439 static void cliVersion(char *cmdline
)
2443 printf("# iNav/%s %s %s / %s (%s)",
2452 static void cliPFlags(char *cmdline
)
2456 printf("# Persistent config flags: 0x%08x", masterConfig
.persistentFlags
);
2459 void cliProcess(void)
2465 while (serialRxBytesWaiting(cliPort
)) {
2466 uint8_t c
= serialRead(cliPort
);
2467 if (c
== '\t' || c
== '?') {
2468 // do tab completion
2469 const clicmd_t
*cmd
, *pstart
= NULL
, *pend
= NULL
;
2470 uint32_t i
= bufferIndex
;
2471 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2472 if (bufferIndex
&& (strncasecmp(cliBuffer
, cmd
->name
, bufferIndex
) != 0))
2478 if (pstart
) { /* Buffer matches one or more commands */
2479 for (; ; bufferIndex
++) {
2480 if (pstart
->name
[bufferIndex
] != pend
->name
[bufferIndex
])
2482 if (!pstart
->name
[bufferIndex
] && bufferIndex
< sizeof(cliBuffer
) - 2) {
2483 /* Unambiguous -- append a space */
2484 cliBuffer
[bufferIndex
++] = ' ';
2485 cliBuffer
[bufferIndex
] = '\0';
2488 cliBuffer
[bufferIndex
] = pstart
->name
[bufferIndex
];
2491 if (!bufferIndex
|| pstart
!= pend
) {
2492 /* Print list of ambiguous matches */
2493 cliPrint("\r\033[K");
2494 for (cmd
= pstart
; cmd
<= pend
; cmd
++) {
2495 cliPrint(cmd
->name
);
2499 i
= 0; /* Redraw prompt */
2501 for (; i
< bufferIndex
; i
++)
2502 cliWrite(cliBuffer
[i
]);
2503 } else if (!bufferIndex
&& c
== 4) { // CTRL-D
2506 } else if (c
== 12) { // NewPage / CTRL-L
2508 cliPrint("\033[2J\033[1;1H");
2510 } else if (bufferIndex
&& (c
== '\n' || c
== '\r')) {
2514 // Strip comment starting with # from line
2515 char *p
= cliBuffer
;
2518 bufferIndex
= (uint32_t)(p
- cliBuffer
);
2521 // Strip trailing whitespace
2522 while (bufferIndex
> 0 && cliBuffer
[bufferIndex
- 1] == ' ') {
2526 // Process non-empty lines
2527 if (bufferIndex
> 0) {
2528 cliBuffer
[bufferIndex
] = 0; // null terminate
2530 const clicmd_t
*cmd
;
2531 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2532 if(!strncasecmp(cliBuffer
, cmd
->name
, strlen(cmd
->name
)) // command names match
2533 && !isalnum((unsigned)cliBuffer
[strlen(cmd
->name
)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2536 if(cmd
< cmdTable
+ CMD_COUNT
)
2537 cmd
->func(cliBuffer
+ strlen(cmd
->name
) + 1);
2539 cliPrint("Unknown command, try 'help'");
2543 memset(cliBuffer
, 0, sizeof(cliBuffer
));
2545 // 'exit' will reset this flag, so we don't need to print prompt again
2550 } else if (c
== 127) {
2553 cliBuffer
[--bufferIndex
] = 0;
2554 cliPrint("\010 \010");
2556 } else if (bufferIndex
< sizeof(cliBuffer
) && c
>= 32 && c
<= 126) {
2557 if (!bufferIndex
&& c
== ' ')
2558 continue; // Ignore leading spaces
2559 cliBuffer
[bufferIndex
++] = c
;
2565 void cliInit(serialConfig_t
*serialConfig
)
2567 UNUSED(serialConfig
);