mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: fix compile warnings re float constants
This commit is contained in:
parent
d6b34209b5
commit
66ddfdeae6
@ -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
|
// add a small amount before casting parameter values
|
||||||
// from float to integer to avoid truncating to the
|
// from float to integer to avoid truncating to the
|
||||||
// next lower integer value.
|
// next lower integer value.
|
||||||
float rounding_addition = 0.01;
|
float rounding_addition = 0.01f;
|
||||||
|
|
||||||
// handle variables with standard type IDs
|
// handle variables with standard type IDs
|
||||||
if (var_type == AP_PARAM_FLOAT) {
|
if (var_type == AP_PARAM_FLOAT) {
|
||||||
|
Loading…
Reference in New Issue
Block a user