mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
PerfMon: fix compile warnings re float constants
This commit is contained in:
parent
66ddfdeae6
commit
2179705791
@ -175,13 +175,13 @@ void AP_PerfMon::DisplayResults()
|
||||
}
|
||||
|
||||
hz = numCalls[j]/(totalTime/1000000);
|
||||
pct = ((float)time[j] / (float)totalTime) * 100.0;
|
||||
pct = ((float)time[j] / (float)totalTime) * 100.0f;
|
||||
hal.console->printf_P(PSTR("%-10s\t%4.2f\t%lu\t%4.3f\t%4.3f\t%lu\t%4.1f\n"),
|
||||
functionNames[j],
|
||||
pct,
|
||||
(unsigned long)time[j]/1000,
|
||||
(float)avgTime/1000.0,
|
||||
(float)maxTime[j]/1000.0,
|
||||
(float)avgTime/1000.0f,
|
||||
(float)maxTime[j]/1000.0f,
|
||||
numCalls[j],
|
||||
hz);
|
||||
}
|
||||
@ -191,7 +191,7 @@ void AP_PerfMon::DisplayResults()
|
||||
} else {
|
||||
unExplainedTime = totalTime - sumOfTime;
|
||||
}
|
||||
pct = ((float)unExplainedTime / (float)totalTime) * 100.0;
|
||||
pct = ((float)unExplainedTime / (float)totalTime) * 100.0f;
|
||||
hal.console->printf_P(PSTR("unexpl:\t\t%4.2f\t%lu\n"),pct,(unsigned long)unExplainedTime/1000);
|
||||
|
||||
// restore to blocking writes if necessary
|
||||
|
Loading…
Reference in New Issue
Block a user