mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_OSD: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
390e0fa601
commit
12a6e9ad69
@ -242,7 +242,7 @@ void AP_OSD::stats()
|
||||
Location loc;
|
||||
if (ahrs.get_position(loc) && ahrs.home_is_set()) {
|
||||
const Location &home_loc = ahrs.get_home();
|
||||
float distance = get_distance(home_loc, loc);
|
||||
float distance = home_loc.get_distance(loc);
|
||||
max_dist_m = fmaxf(max_dist_m, distance);
|
||||
}
|
||||
|
||||
|
@ -629,7 +629,7 @@ void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
|
||||
Location loc;
|
||||
if (ahrs.get_position(loc) && ahrs.home_is_set()) {
|
||||
const Location &home_loc = ahrs.get_home();
|
||||
float distance = get_distance(home_loc, loc);
|
||||
float distance = home_loc.get_distance(loc);
|
||||
int32_t angle = wrap_360_cd(get_bearing_cd(loc, home_loc) - ahrs.yaw_sensor);
|
||||
int32_t interval = 36000 / SYM_ARROW_COUNT;
|
||||
if (distance < 2.0f) {
|
||||
|
Loading…
Reference in New Issue
Block a user