mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_AIS: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
ff63b62b0c
commit
45733c96ac
@ -292,7 +292,7 @@ bool AP_AIS::get_vessel_index(uint32_t mmsi, uint16_t &index, uint32_t lat, uint
|
||||
}
|
||||
|
||||
struct Location current_loc;
|
||||
if (!AP::ahrs().get_position(current_loc)) {
|
||||
if (!AP::ahrs().get_location(current_loc)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user