From 2179705791c68ecfe870109821ce502bff867594 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 12:59:35 +0900 Subject: [PATCH] PerfMon: fix compile warnings re float constants --- libraries/AP_PerfMon/AP_PerfMon.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_PerfMon/AP_PerfMon.cpp b/libraries/AP_PerfMon/AP_PerfMon.cpp index e5e43dc980..7024587d1b 100644 --- a/libraries/AP_PerfMon/AP_PerfMon.cpp +++ b/libraries/AP_PerfMon/AP_PerfMon.cpp @@ -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