mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AC_Avoidance: use AP_Math control functions
This commit is contained in:
parent
e2308e9414
commit
4e2c7880c5
@ -414,7 +414,7 @@ float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, flo
|
|||||||
if (is_zero(kP)) {
|
if (is_zero(kP)) {
|
||||||
return safe_sqrt(2.0f * distance_cm * accel_cmss);
|
return safe_sqrt(2.0f * distance_cm * accel_cmss);
|
||||||
} else {
|
} else {
|
||||||
return AC_AttitudeControl::sqrt_controller(distance_cm, kP, accel_cmss, dt);
|
return sqrt_controller(distance_cm, kP, accel_cmss, dt);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user