AP_HAL: Unify from print or println to printf.
This commit is contained in:
parent
af47a8e91c
commit
03bf57219b
@ -15,7 +15,7 @@ void loop (void)
|
||||
{
|
||||
float v = ch->voltage_average();
|
||||
if (pin == 0) {
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
hal.console->printf("[%u %.3f] ",
|
||||
(unsigned)pin, v);
|
||||
|
@ -4,7 +4,7 @@
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void setup(void) {
|
||||
hal.console->println("Starting Printf test");
|
||||
hal.console->printf("Starting Printf test\n");
|
||||
}
|
||||
|
||||
static const struct {
|
||||
|
@ -39,7 +39,7 @@ void loop(void)
|
||||
for (uint8_t i = 0; i < max_channels_display; i++) {
|
||||
hal.console->printf("%2u:%04u ", (unsigned)i+1, (unsigned)last_value[i]);
|
||||
}
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
} else {
|
||||
hal.console->printf("Channels detected: %2u\n", nchannels);
|
||||
|
@ -46,7 +46,7 @@ void loop(void)
|
||||
for(uint8_t i = 0; i < max_channels; i++) {
|
||||
hal.console->printf("%2u:%04u ", (unsigned)i + 1, (unsigned)last_value[i]);
|
||||
}
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
|
@ -8,7 +8,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void setup (void)
|
||||
{
|
||||
hal.console->println("Starting AP_HAL::RCOutput test");
|
||||
hal.console->printf("Starting AP_HAL::RCOutput test\n");
|
||||
for (uint8_t i=0; i<14; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
}
|
||||
|
@ -72,7 +72,7 @@ const struct Menu::command rcoutput_menu_commands[] = {
|
||||
MENU(menu, "Menu: ", rcoutput_menu_commands);
|
||||
|
||||
void setup(void) {
|
||||
hal.console->println("Starting AP_HAL::RCOutput test");
|
||||
hal.console->printf("Starting AP_HAL::RCOutput test\n");
|
||||
|
||||
for (uint8_t i = 0; i < 14; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
|
Loading…
Reference in New Issue
Block a user