mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: use fast_atan2 for bearings to home and next WP
This commit is contained in:
parent
919b0ea29b
commit
083f2898a9
@ -17,7 +17,7 @@ Vector3f pv_location_to_vector(const Location& loc)
|
||||
// pv_get_bearing_cd - return bearing in centi-degrees between two positions
|
||||
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
|
||||
{
|
||||
float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * DEGX100;
|
||||
float bearing = 9000 + fast_atan2(-(destination.x-origin.x), destination.y-origin.y) * DEGX100;
|
||||
if (bearing < 0) {
|
||||
bearing += 36000;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user