mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tools: Unify from print or println to printf.
This commit is contained in:
parent
3ce2ca488a
commit
334da0d9d5
@ -15,7 +15,7 @@ void setup() {
|
|||||||
|
|
||||||
static void show_sizes(void)
|
static void show_sizes(void)
|
||||||
{
|
{
|
||||||
hal.console->println("Type sizes:");
|
hal.console->printf("Type sizes:\n");
|
||||||
hal.console->printf("char : %lu\n", (unsigned long)sizeof(char));
|
hal.console->printf("char : %lu\n", (unsigned long)sizeof(char));
|
||||||
hal.console->printf("short : %lu\n", (unsigned long)sizeof(short));
|
hal.console->printf("short : %lu\n", (unsigned long)sizeof(short));
|
||||||
hal.console->printf("int : %lu\n", (unsigned long)sizeof(int));
|
hal.console->printf("int : %lu\n", (unsigned long)sizeof(int));
|
||||||
@ -72,8 +72,8 @@ static void show_timings(void)
|
|||||||
v_out_8 = 1+(AP_HAL::micros() % 3);
|
v_out_8 = 1+(AP_HAL::micros() % 3);
|
||||||
|
|
||||||
|
|
||||||
hal.console->println("Operation timings:");
|
hal.console->printf("Operation timings:\n");
|
||||||
hal.console->println("Note: timings for some operations are very data dependent");
|
hal.console->printf("Note: timings for some operations are very data dependent\n");
|
||||||
|
|
||||||
TIMEIT("nop", asm volatile("nop"::), 255);
|
TIMEIT("nop", asm volatile("nop"::), 255);
|
||||||
|
|
||||||
@ -127,9 +127,9 @@ static void show_timings(void)
|
|||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
show_sizes();
|
show_sizes();
|
||||||
hal.console->println("");
|
hal.console->printf("\n");
|
||||||
show_timings();
|
show_timings();
|
||||||
hal.console->println("");
|
hal.console->printf("\n");
|
||||||
hal.scheduler->delay(3000);
|
hal.scheduler->delay(3000);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -9,13 +9,13 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
hal.console->println("hello world");
|
hal.console->printf("hello world\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
hal.console->println("*");
|
hal.console->printf("*\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
Loading…
Reference in New Issue
Block a user