1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Code and documentation cleanup of rc calibration.

Note: since it didn't actually calibrate anything it has been renamed to
rxrange.

Added ability to reset rxranges using `rxrange reset` - this follows the
same pattern as other cli commands.
This commit is contained in:
Dominic Clifton 2015-08-04 00:23:38 +01:00
parent 27f8223de7
commit 9d3276b222
9 changed files with 103 additions and 87 deletions

View file

@ -117,7 +117,7 @@ static void cliSet(char *cmdline);
static void cliGet(char *cmdline);
static void cliStatus(char *cmdline);
static void cliVersion(char *cmdline);
static void cliRxCalibration(char *cmdline);
static void cliRxRange(char *cmdline);
#ifdef GPS
static void cliGpsPassthrough(char *cmdline);
@ -258,8 +258,8 @@ const clicmd_t cmdTable[] = {
"[<index>]", cliProfile),
CLI_COMMAND_DEF("rateprofile", "change rate profile",
"[<index>]", cliRateProfile),
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
CLI_COMMAND_DEF("rxcal", "rc calibration", NULL, cliRxCalibration),
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
#ifdef USE_SERVOS
@ -929,42 +929,47 @@ static void cliMotorMix(char *cmdline)
#endif
}
static void cliRxCalibration(char *cmdline)
static void cliRxRange(char *cmdline)
{
int i, check = 0;
int i, validArgumentCount = 0;
char *ptr;
if (isEmpty(cmdline)) {
for (i = 0; i < MAX_CALIBRATED_RX_CHANNELS; i++) {
printf("rccal %u %u %u\r\n", i, masterConfig.rxConfig.calibration[i].minrc, masterConfig.rxConfig.calibration[i].maxrc);
for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
printf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
}
} else if (strcasecmp(cmdline, "reset") == 0) {
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
} else {
ptr = cmdline;
i = atoi(ptr);
if (i >= 0 && i < MAX_CALIBRATED_RX_CHANNELS) {
int minrc, maxrc;
if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
int rangeMin, rangeMax;
ptr = strchr(ptr, ' ');
if (ptr) {
minrc = atoi(++ptr);
check++;
rangeMin = atoi(++ptr);
validArgumentCount++;
}
ptr = strchr(ptr, ' ');
if (ptr) {
maxrc = atoi(++ptr);
check++;
rangeMax = atoi(++ptr);
validArgumentCount++;
}
if (check != 2) {
printf("Wrong number of arguments, needs idx min max\r\n");
}
else if (minrc < 750 || minrc > 2250 || maxrc < 750 || maxrc > 2250 || minrc >= maxrc) {
printf("Parameters error. Should be: 750 <= minrc < maxrc <= 2250\r\n");
}
else {
masterConfig.rxConfig.calibration[i].minrc = minrc;
masterConfig.rxConfig.calibration[i].maxrc = maxrc;
if (validArgumentCount != 2) {
cliShowParseError();
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX || rangeMin >= rangeMax) {
cliShowParseError();
} else {
rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
channelRangeConfiguration->min = rangeMin;
channelRangeConfiguration->max = rangeMax;
}
} else {
printf("Invalid R/C channel: must be > 0 and < %u\r\n", MAX_CALIBRATED_RX_CHANNELS);
cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
}
}
}
@ -1509,9 +1514,9 @@ static void cliDump(char *cmdline)
cliAdjustmentRange("");
printf("\r\n# rccal\r\n");
printf("\r\n# rxrange\r\n");
cliRxCalibration("");
cliRxRange("");
cliPrint("\r\n# servo\r\n");