mirror of https://github.com/ArduPilot/ardupilot
Tools/CPUInfo: type conversion
This commit is contained in:
parent
b260a6ca7c
commit
797fc84e92
|
@ -42,7 +42,7 @@ static void show_sizes(void)
|
|||
FIFTYTIMES(op); \
|
||||
} \
|
||||
us_end = AP_HAL::micros(); \
|
||||
hal.console->printf("%-10s %7.2f usec/call\n", name, double(us_end - us_start) / (count * 50.0)); \
|
||||
hal.console->printf("%-10s %7.2f usec/call\n", name, double(us_end - us_start) / double(count * 50.0)); \
|
||||
} while (0)
|
||||
|
||||
volatile float v_f = 1.0;
|
||||
|
|
Loading…
Reference in New Issue