From 198ada2b4222e2050770c12baac41b5fc0f9d13f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 20:26:20 +1000 Subject: [PATCH] APM_Control: avoid some float conversion warnings --- libraries/APM_Control/AP_RollController.cpp | 2 +- libraries/APM_Control/AP_SteerController.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index f67d030e75..b1dbe00502 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -189,7 +189,7 @@ int32_t AP_RollController::get_rate_out(float desired_rate, float scaler) */ int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator) { - if (gains.tau < 0.1) { + if (gains.tau < 0.1f) { gains.tau.set(0.1f); } diff --git a/libraries/APM_Control/AP_SteerController.cpp b/libraries/APM_Control/AP_SteerController.cpp index 711d6143d2..ff61c0ae4b 100644 --- a/libraries/APM_Control/AP_SteerController.cpp +++ b/libraries/APM_Control/AP_SteerController.cpp @@ -167,8 +167,8 @@ int32_t AP_SteerController::get_steering_out_lat_accel(float desired_accel) */ int32_t AP_SteerController::get_steering_out_angle_error(int32_t angle_err) { - if (_tau < 0.1) { - _tau = 0.1; + if (_tau < 0.1f) { + _tau = 0.1f; } // Calculate the desired steering rate (deg/sec) from the angle error