mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_OSD: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
88b463947a
commit
26c4b65d4e
@ -370,7 +370,7 @@ void AP_OSD::update_stats()
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
WITH_SEMAPHORE(ahrs.get_semaphore());
|
||||
v = ahrs.groundspeed_vector();
|
||||
home_is_set = ahrs.get_position(loc) && ahrs.home_is_set();
|
||||
home_is_set = ahrs.get_location(loc) && ahrs.home_is_set();
|
||||
if (home_is_set) {
|
||||
home_loc = ahrs.get_home();
|
||||
}
|
||||
|
@ -1559,7 +1559,7 @@ void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
WITH_SEMAPHORE(ahrs.get_semaphore());
|
||||
Location loc;
|
||||
if (ahrs.get_position(loc) && ahrs.home_is_set()) {
|
||||
if (ahrs.get_location(loc) && ahrs.home_is_set()) {
|
||||
const Location &home_loc = ahrs.get_home();
|
||||
float distance = home_loc.get_distance(loc);
|
||||
int32_t angle = wrap_360_cd(loc.get_bearing_to(home_loc) - ahrs.yaw_sensor);
|
||||
|
Loading…
Reference in New Issue
Block a user