APMrover2: Change from printf statement to print, println statement.

This commit is contained in:
murata 2016-11-26 02:03:35 +09:00 committed by Tom Pittenger
parent 0ee8edc29d
commit bbf0cfb564
4 changed files with 20 additions and 20 deletions

View File

@ -23,10 +23,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&rover, &Rover::print_log
bool Rover::print_log_menu(void)
{
cliSerial->printf("logs enabled: ");
cliSerial->print("logs enabled: ");
if (0 == g.log_bitmask) {
cliSerial->printf("none");
cliSerial->print("none");
}else{
// Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined
@ -69,11 +69,11 @@ int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv)
DataFlash.DumpPageInfo(cliSerial);
return(-1);
} else if (dump_log_num <= 0) {
cliSerial->printf("dumping all\n");
cliSerial->println("dumping all");
Log_Read(0, 1, 0);
return(-1);
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
cliSerial->printf("bad log number\n");
cliSerial->println("bad log number");
return(-1);
}
@ -96,7 +96,7 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
uint16_t bits;
if (argc != 2) {
cliSerial->printf("missing log type\n");
cliSerial->println("missing log type");
return(-1);
}

View File

@ -610,7 +610,7 @@ const AP_Param::ConversionInfo conversion_table[] = {
void Rover::load_parameters(void)
{
if (!AP_Param::check_var_info()) {
cliSerial->printf("Bad var table\n");
cliSerial->println("Bad var table");
AP_HAL::panic("Bad var table");
}
@ -618,7 +618,7 @@ void Rover::load_parameters(void)
g.format_version != Parameters::k_format_version) {
// erase all parameters
cliSerial->printf("Firmware change: erasing EEPROM...\n");
cliSerial->println("Firmware change: erasing EEPROM...");
AP_Param::erase_all();
// save the current format version

View File

@ -48,7 +48,7 @@ void Rover::zero_eeprom(void)
{
cliSerial->printf("\nErasing EEPROM\n");
StorageManager::erase();
cliSerial->printf("done\n");
cliSerial->println("done");
}
#endif // CLI_ENABLED

View File

@ -147,7 +147,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
oldSwitchPosition = readSwitch();
cliSerial->printf("Unplug battery, throttle in neutral, turn off radio.\n");
cliSerial->println("Unplug battery, throttle in neutral, turn off radio.");
while(channel_throttle->get_control_in() > 0){
delay(20);
read_radio();
@ -163,7 +163,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
}
if (oldSwitchPosition != readSwitch()){
cliSerial->printf("CONTROL MODE CHANGED: ");
cliSerial->print("CONTROL MODE CHANGED: ");
print_mode(cliSerial, readSwitch());
cliSerial->println();
fail_test++;
@ -180,7 +180,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
return (0);
}
if(cliSerial->available() > 0){
cliSerial->printf("LOS caused no change in APM.\n");
cliSerial->println("LOS caused no change in APM.");
return (0);
}
}
@ -192,14 +192,14 @@ int8_t Rover::test_relay(uint8_t argc, const Menu::arg *argv)
delay(1000);
while(1){
cliSerial->printf("Relay on\n");
cliSerial->println("Relay on");
relay.on(0);
delay(3000);
if(cliSerial->available() > 0){
return (0);
}
cliSerial->printf("Relay off\n");
cliSerial->println("Relay off");
relay.off(0);
delay(3000);
if(cliSerial->available() > 0){
@ -242,7 +242,7 @@ int8_t Rover::test_modeswitch(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
cliSerial->printf("Control CH ");
cliSerial->print("Control CH ");
cliSerial->println(MODE_CHANNEL, BASE_DEC);
@ -293,7 +293,7 @@ int8_t Rover::test_gps(uint8_t argc, const Menu::arg *argv)
(long)loc.alt/100,
(int)gps.num_sats());
} else {
cliSerial->printf(".");
cliSerial->print(".");
}
if(cliSerial->available() > 0) {
return (0);
@ -303,7 +303,7 @@ int8_t Rover::test_gps(uint8_t argc, const Menu::arg *argv)
int8_t Rover::test_ins(uint8_t argc, const Menu::arg *argv)
{
//cliSerial->printf("Calibrating.");
//cliSerial->print("Calibrating.");
ahrs.init();
ahrs.set_fly_forward(true);
@ -347,16 +347,16 @@ int8_t Rover::test_ins(uint8_t argc, const Menu::arg *argv)
void Rover::print_enabled(bool b)
{
if(b)
cliSerial->printf("en");
cliSerial->print("en");
else
cliSerial->printf("dis");
cliSerial->printf("abled\n");
cliSerial->print("dis");
cliSerial->println("abled");
}
int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
{
if (!g.compass_enabled) {
cliSerial->printf("Compass: ");
cliSerial->print("Compass: ");
print_enabled(false);
return (0);
}