From b276034c6058bf4bfad8ec95f9938def91a0d4b0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Oct 2018 21:08:15 +1100 Subject: [PATCH] APM_Control: correct use of incorrect abs functions --- libraries/APM_Control/AP_PitchController.cpp | 2 +- libraries/APM_Control/AR_AttitudeControl.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index bfc28b5e8d..964c6f7a88 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -211,7 +211,7 @@ int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool beyond the configured roll limit, reducing to zero at 90 degrees */ - float roll_wrapped = fabsf(_ahrs.roll_sensor); + float roll_wrapped = labs(_ahrs.roll_sensor); if (roll_wrapped > 9000) { roll_wrapped = 18000 - roll_wrapped; } diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 6485e0612c..ec565f4875 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -659,7 +659,7 @@ bool AR_AttitudeControl::get_forward_speed(float &speed) const if (!_ahrs.get_velocity_NED(velocity)) { // use less accurate GPS, assuming entire length is along forward/back axis of vehicle if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) { - if (labs(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) { + if (fabsf(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) { speed = AP::gps().ground_speed(); } else { speed = -AP::gps().ground_speed();