mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Landing: use get_distance instead of location_diff
This commit is contained in:
parent
6397cb0c0e
commit
0b50f32c32
@ -632,7 +632,7 @@ float AP_Landing_Deepstall::update_steering()
|
||||
(double)crosstrack_error,
|
||||
(double)error,
|
||||
(double)degrees(yaw_rate),
|
||||
(double)location_diff(current_loc, landing_point).length());
|
||||
(double)current_loc.get_distance(landing_point));
|
||||
#endif // DEBUG_PRINTS
|
||||
|
||||
return ds_PID.get_pid(error);
|
||||
|
Loading…
Reference in New Issue
Block a user