AP_Param: fix compile warnings re float constants

This commit is contained in:
Tom Pittenger 2015-04-24 12:57:36 +09:00 committed by Randy Mackay
parent d6b34209b5
commit 66ddfdeae6

View File

@ -1223,7 +1223,7 @@ AP_Param *AP_Param::set_param_by_name(const char *pname, float value, enum ap_va
// add a small amount before casting parameter values
// from float to integer to avoid truncating to the
// next lower integer value.
float rounding_addition = 0.01;
float rounding_addition = 0.01f;
// handle variables with standard type IDs
if (var_type == AP_PARAM_FLOAT) {