From b9771ca37cdb72924fb02cfe7d035bdfa8aed50d Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 2 May 2015 23:04:23 -0700 Subject: [PATCH] AP_Param: compile warnings: float to double. print statements require doubles --- libraries/AP_Param/AP_Param.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 2ac444eef5..779afdcc55 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1094,7 +1094,7 @@ void AP_Param::show(const AP_Param *ap, const char *s, port->printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get()); break; case AP_PARAM_FLOAT: - port->printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get()); + port->printf_P(PSTR("%s: %f\n"), s, (double)((AP_Float *)ap)->get()); break; default: break;