mirror of https://github.com/ArduPilot/ardupilot
Copter: Change from printf statement to print, println statement.
This commit is contained in:
parent
bbf0cfb564
commit
f7273d0e93
|
@ -24,10 +24,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&copter, &Copter::print_l
|
|||
|
||||
bool Copter::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
|
||||
|
@ -73,11 +73,11 @@ int8_t Copter::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);
|
||||
}
|
||||
|
||||
|
@ -100,7 +100,7 @@ int8_t Copter::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);
|
||||
}
|
||||
|
||||
|
|
|
@ -1085,7 +1085,7 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
|||
void Copter::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");
|
||||
}
|
||||
|
||||
|
@ -1097,7 +1097,7 @@ void Copter::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
|
||||
|
|
|
@ -69,7 +69,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
if(argc!=3)
|
||||
{
|
||||
cliSerial->printf("Invalid command. Usage: set <name> <value>\n");
|
||||
cliSerial->println("Invalid command. Usage: set <name> <value>");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -178,7 +178,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
|
||||
set_mask = strtol (argv[1].str, nullptr, 2);
|
||||
if (set_mask == 0)
|
||||
cliSerial->printf("no channels chosen");
|
||||
cliSerial->print("no channels chosen");
|
||||
//cliSerial->printf("\n%d\n",set_mask);
|
||||
set_mask<<=1;
|
||||
/* wait 50 ms */
|
||||
|
@ -224,7 +224,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
motors.armed(true);
|
||||
|
||||
|
||||
cliSerial->printf("Outputs armed\n");
|
||||
cliSerial->println("Outputs armed");
|
||||
|
||||
|
||||
/* wait for user confirmation */
|
||||
|
@ -286,7 +286,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
/* disarm */
|
||||
motors.armed(false);
|
||||
|
||||
cliSerial->printf("Outputs disarmed\n");
|
||||
cliSerial->println("Outputs disarmed");
|
||||
|
||||
cliSerial->printf("%s finished\n", strEscCalib);
|
||||
|
||||
|
@ -305,30 +305,30 @@ void Copter::report_batt_monitor()
|
|||
if (battery.num_instances() == 0) {
|
||||
print_enabled(false);
|
||||
} else if (!battery.has_current()) {
|
||||
cliSerial->printf("volts");
|
||||
cliSerial->print("volts");
|
||||
} else {
|
||||
cliSerial->printf("volts and cur");
|
||||
cliSerial->print("volts and cur");
|
||||
}
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
void Copter::report_frame()
|
||||
{
|
||||
cliSerial->printf("Frame\n");
|
||||
cliSerial->println("Frame");
|
||||
print_divider();
|
||||
|
||||
#if FRAME_CONFIG == QUAD_FRAME
|
||||
cliSerial->printf("Quad frame\n");
|
||||
cliSerial->println("Quad frame");
|
||||
#elif FRAME_CONFIG == TRI_FRAME
|
||||
cliSerial->printf("TRI frame\n");
|
||||
cliSerial->println("TRI frame");
|
||||
#elif FRAME_CONFIG == HEXA_FRAME
|
||||
cliSerial->printf("Hexa frame\n");
|
||||
cliSerial->println("Hexa frame");
|
||||
#elif FRAME_CONFIG == Y6_FRAME
|
||||
cliSerial->printf("Y6 frame\n");
|
||||
cliSerial->println("Y6 frame");
|
||||
#elif FRAME_CONFIG == OCTA_FRAME
|
||||
cliSerial->printf("Octa frame\n");
|
||||
cliSerial->println("Octa frame");
|
||||
#elif FRAME_CONFIG == HELI_FRAME
|
||||
cliSerial->printf("Heli frame\n");
|
||||
cliSerial->println("Heli frame");
|
||||
#endif
|
||||
|
||||
print_blanks(2);
|
||||
|
@ -336,7 +336,7 @@ void Copter::report_frame()
|
|||
|
||||
void Copter::report_radio()
|
||||
{
|
||||
cliSerial->printf("Radio\n");
|
||||
cliSerial->println("Radio");
|
||||
print_divider();
|
||||
// radio
|
||||
print_radio_values();
|
||||
|
@ -345,7 +345,7 @@ void Copter::report_radio()
|
|||
|
||||
void Copter::report_ins()
|
||||
{
|
||||
cliSerial->printf("INS\n");
|
||||
cliSerial->println("INS");
|
||||
print_divider();
|
||||
|
||||
print_gyro_offsets();
|
||||
|
@ -355,7 +355,7 @@ void Copter::report_ins()
|
|||
|
||||
void Copter::report_flight_modes()
|
||||
{
|
||||
cliSerial->printf("Flight modes\n");
|
||||
cliSerial->println("Flight modes");
|
||||
print_divider();
|
||||
|
||||
for(int16_t i = 0; i < 6; i++ ) {
|
||||
|
@ -367,7 +367,7 @@ void Copter::report_flight_modes()
|
|||
void Copter::report_optflow()
|
||||
{
|
||||
#if OPTFLOW == ENABLED
|
||||
cliSerial->printf("OptFlow\n");
|
||||
cliSerial->println("OptFlow");
|
||||
print_divider();
|
||||
|
||||
print_enabled(optflow.enabled());
|
||||
|
@ -398,9 +398,9 @@ void Copter::print_switch(uint8_t p, uint8_t m, bool b)
|
|||
print_flight_mode(cliSerial, m);
|
||||
cliSerial->printf(",\t\tSimple: ");
|
||||
if(b)
|
||||
cliSerial->printf("ON\n");
|
||||
cliSerial->println("ON");
|
||||
else
|
||||
cliSerial->printf("OFF\n");
|
||||
cliSerial->println("OFF");
|
||||
}
|
||||
|
||||
void Copter::print_accel_offsets_and_scaling(void)
|
||||
|
@ -430,7 +430,7 @@ void Copter::print_gyro_offsets(void)
|
|||
// report_compass - displays compass information. Also called by compassmot.pde
|
||||
void Copter::report_compass()
|
||||
{
|
||||
cliSerial->printf("Compass\n");
|
||||
cliSerial->println("Compass");
|
||||
print_divider();
|
||||
|
||||
print_enabled(g.compass_enabled);
|
||||
|
@ -454,7 +454,7 @@ void Copter::report_compass()
|
|||
// motor compensation
|
||||
cliSerial->print("Motor Comp: ");
|
||||
if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) {
|
||||
cliSerial->print("Off\n");
|
||||
cliSerial->println("Off");
|
||||
}else{
|
||||
if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) {
|
||||
cliSerial->print("Throttle");
|
||||
|
@ -497,7 +497,7 @@ void Copter::print_enabled(bool b)
|
|||
cliSerial->print("en");
|
||||
else
|
||||
cliSerial->print("dis");
|
||||
cliSerial->print("abled\n");
|
||||
cliSerial->println("abled");
|
||||
}
|
||||
|
||||
void Copter::report_version()
|
||||
|
|
|
@ -63,7 +63,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
uint8_t medium_loopCounter = 0;
|
||||
|
||||
if (!g.compass_enabled) {
|
||||
cliSerial->printf("Compass: ");
|
||||
cliSerial->print("Compass: ");
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}
|
||||
|
@ -146,12 +146,12 @@ int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
Vector3f gyro, accel;
|
||||
print_hit_enter();
|
||||
cliSerial->printf("INS\n");
|
||||
cliSerial->println("INS");
|
||||
delay(1000);
|
||||
|
||||
ahrs.init();
|
||||
ins.init(scheduler.get_loop_rate_hz());
|
||||
cliSerial->printf("...done\n");
|
||||
cliSerial->println("...done");
|
||||
|
||||
delay(50);
|
||||
|
||||
|
@ -195,7 +195,7 @@ int8_t Copter::test_optflow(uint8_t argc, const Menu::arg *argv)
|
|||
}
|
||||
}
|
||||
} else {
|
||||
cliSerial->printf("OptFlow: ");
|
||||
cliSerial->print("OptFlow: ");
|
||||
print_enabled(false);
|
||||
}
|
||||
return (0);
|
||||
|
@ -210,14 +210,14 @@ int8_t Copter::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) {
|
||||
|
|
Loading…
Reference in New Issue