mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
APM_PI: fix compile warnings re float constants
This commit is contained in:
parent
b9865c5f3e
commit
2f9e0c1938
@ -23,9 +23,9 @@ public:
|
||||
/// @param initial_i Initial value for the I term.
|
||||
/// @param initial_imax Initial value for the imax term.4
|
||||
///
|
||||
APM_PI(const float & initial_p = 0.0,
|
||||
const float & initial_i = 0.0,
|
||||
const int16_t & initial_imax = 0.0)
|
||||
APM_PI(const float & initial_p = 0.0f,
|
||||
const float & initial_i = 0.0f,
|
||||
const int16_t & initial_imax = 0.0f)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_kp = initial_p;
|
||||
|
Loading…
Reference in New Issue
Block a user