mirror of https://github.com/ArduPilot/ardupilot
Copter: reduce repeated string constants
This commit is contained in:
parent
af5a2ea0c6
commit
f135ca5ae7
|
@ -82,13 +82,14 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
return 0;
|
||||
}
|
||||
|
||||
const char *strType = "Value out of range for type";
|
||||
switch(p_type)
|
||||
{
|
||||
case AP_PARAM_INT8:
|
||||
value_int8 = (int8_t)(argv[2].i);
|
||||
if(argv[2].i!=value_int8)
|
||||
{
|
||||
cliSerial->printf("Value out of range for type INT8\n");
|
||||
cliSerial->printf("%s INT8\n", strType);
|
||||
return 0;
|
||||
}
|
||||
((AP_Int8*)param)->set_and_save(value_int8);
|
||||
|
@ -97,7 +98,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
value_int16 = (int16_t)(argv[2].i);
|
||||
if(argv[2].i!=value_int16)
|
||||
{
|
||||
cliSerial->printf("Value out of range for type INT16\n");
|
||||
cliSerial->printf("%s INT16\n", strType);
|
||||
return 0;
|
||||
}
|
||||
((AP_Int16*)param)->set_and_save(value_int16);
|
||||
|
@ -196,6 +197,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
"Do you want to start calibration now: y or n?\n");
|
||||
|
||||
/* wait for user input */
|
||||
const char *strEscCalib = "ESC calibration";
|
||||
while (1) {
|
||||
c= cliSerial->read();
|
||||
if (c == 'y' || c == 'Y') {
|
||||
|
@ -203,11 +205,11 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
cliSerial->printf("ESC calibration exited\n");
|
||||
cliSerial->printf("%s exited\n", strEscCalib);
|
||||
return(0);
|
||||
|
||||
} else if (c == 'n' || c == 'N') {
|
||||
cliSerial->printf("ESC calibration aborted\n");
|
||||
cliSerial->printf("%s aborted\n", strEscCalib);
|
||||
return(0);
|
||||
|
||||
}
|
||||
|
@ -247,7 +249,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 'q') {
|
||||
cliSerial->printf("ESC calibration exited\n");
|
||||
cliSerial->printf("%s exited\n", strEscCalib);
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -275,7 +277,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 'q') {
|
||||
cliSerial->printf("ESC calibration exited\n");
|
||||
cliSerial->printf("%s exited\n", strEscCalib);
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -288,7 +290,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
|
||||
cliSerial->printf("Outputs disarmed\n");
|
||||
|
||||
cliSerial->printf("ESC calibration finished\n");
|
||||
cliSerial->printf("%s finished\n", strEscCalib);
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue