AC_PID: fix compile warnings re float constants

This commit is contained in:
Tom Pittenger 2015-04-24 12:22:40 +09:00 committed by Randy Mackay
parent bd9b573969
commit 4b97cc1957
2 changed files with 6 additions and 6 deletions

View File

@ -24,7 +24,7 @@ public:
/// @param initial_p Initial value for the P term.
///
AC_P(
const float & initial_p = 0.0)
const float & initial_p = 0.0f)
{
AP_Param::setup_object_defaults(this, var_info);
_kp = initial_p;

View File

@ -40,12 +40,12 @@
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// default PID values
#define TEST_P 1.0
#define TEST_I 0.01
#define TEST_D 0.2
#define TEST_P 1.0f
#define TEST_I 0.01f
#define TEST_D 0.2f
#define TEST_IMAX 10
#define TEST_FILTER 5.0
#define TEST_DT 0.01
#define TEST_FILTER 5.0f
#define TEST_DT 0.01f
// setup function
void setup()