From 59610ebe883a4165add62de9c29fa8d639b1538f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Oct 2014 16:15:34 +1100 Subject: [PATCH] AP_L1_Control: fixed some warnings --- libraries/AP_L1_Control/AP_L1_Control.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 965f65542d..f774c6101b 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -114,9 +114,9 @@ float AP_L1_Control::crosstrack_error(void) const */ void AP_L1_Control::_prevent_indecision(float &Nu) { - const float Nu_limit = 0.9f*M_PI; - if (fabs(Nu) > Nu_limit && - fabs(_last_Nu) > Nu_limit && + const float Nu_limit = 0.9f*M_PI_F; + if (fabsf(Nu) > Nu_limit && + fabsf(_last_Nu) > Nu_limit && fabsf(wrap_180_cd(_target_bearing_cd - _ahrs.yaw_sensor)) > 12000 && Nu * _last_Nu < 0.0f) { // we are moving away from the target waypoint and pointing @@ -269,7 +269,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius // if too close to the waypoint, use the velocity vector // if the velocity vector is too small, use the heading vector Vector2f A_air_unit; - if (A_air.length() > 0.1) { + if (A_air.length() > 0.1f) { A_air_unit = A_air.normalized(); } else { if (_groundspeed_vector.length() < 0.1f) {