APM_Control: correct use of incorrect abs functions

This commit is contained in:
Peter Barker 2018-10-09 21:08:15 +11:00 committed by Peter Barker
parent 99090b7170
commit b276034c60
2 changed files with 2 additions and 2 deletions

View File

@ -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;
}

View File

@ -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();