mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Tracker: replace abs with labs for yaw servo
This commit is contained in:
parent
608bb3d611
commit
f7f5040d2d
@ -212,7 +212,7 @@ static void update_yaw_position_servo(float yaw)
|
||||
|
||||
// handle hitting servo limits
|
||||
if (abs(channel_yaw.servo_out) == 18000 &&
|
||||
abs(angle_err) > margin &&
|
||||
labs(angle_err) > margin &&
|
||||
making_progress &&
|
||||
hal.scheduler->millis() - slew_start_ms > g.min_reverse_time*1000) {
|
||||
// we are at the limit of the servo and are not moving in the
|
||||
|
Loading…
Reference in New Issue
Block a user