AP_Param: compile warnings: float to double. print statements require doubles

This commit is contained in:
Tom Pittenger 2015-05-02 23:04:23 -07:00 committed by Andrew Tridgell
parent 330e4126bb
commit b9771ca37c

View File

@ -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()); port->printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get());
break; break;
case AP_PARAM_FLOAT: 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; break;
default: default:
break; break;