mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AC_AutoTune: correct abs to fabsf for roll_cd and pitch_cd
This commit is contained in:
parent
d32a7b3a29
commit
9cd30083a4
@ -439,13 +439,13 @@ bool AC_AutoTune::currently_level()
|
||||
}
|
||||
|
||||
if (!check_level(LevelIssue::ANGLE_ROLL,
|
||||
abs(ahrs_view->roll_sensor - roll_cd),
|
||||
fabsf(ahrs_view->roll_sensor - roll_cd),
|
||||
threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!check_level(LevelIssue::ANGLE_PITCH,
|
||||
abs(ahrs_view->pitch_sensor - pitch_cd),
|
||||
fabsf(ahrs_view->pitch_sensor - pitch_cd),
|
||||
threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user