AP_Math: move get_bearing_cd to Location and rename to get_bearing_to
This commit is contained in:
parent
288ae80a59
commit
88b29ff18c
@ -76,7 +76,7 @@ static void test_one_offset(const struct Location &loc,
|
||||
hal.console->printf("location_offset took %u usec\n",
|
||||
(unsigned)(AP_HAL::micros() - t1));
|
||||
dist2 = loc.get_distance(loc2);
|
||||
bearing2 = get_bearing_cd(loc, loc2) * 0.01f;
|
||||
bearing2 = loc.get_bearing_to(loc2) * 0.01f;
|
||||
float brg_error = bearing2-bearing;
|
||||
if (brg_error > 180) {
|
||||
brg_error -= 360;
|
||||
|
@ -30,16 +30,6 @@ float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destina
|
||||
return norm(destination.x-origin.x,destination.y-origin.y);
|
||||
}
|
||||
|
||||
// return bearing in centi-degrees between two locations
|
||||
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
|
||||
{
|
||||
int32_t off_x = loc2.lng - loc1.lng;
|
||||
const int32_t off_y = (loc2.lat - loc1.lat) / loc2.longitude_scale();
|
||||
int32_t bearing = 9000 + atan2f(-off_y, off_x) * DEGX100;
|
||||
if (bearing < 0) bearing += 36000;
|
||||
return bearing;
|
||||
}
|
||||
|
||||
// return bearing in centi-degrees between two positions
|
||||
float get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
|
||||
{
|
||||
|
@ -22,9 +22,6 @@
|
||||
// return horizontal distance in centimeters between two positions
|
||||
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination);
|
||||
|
||||
// return bearing in centi-degrees between two locations
|
||||
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2);
|
||||
|
||||
// return bearing in centi-degrees between two positions
|
||||
float get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user