mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Frsky_Telem: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
88afef4cdc
commit
423bd1e8a4
@ -77,7 +77,7 @@ void AP_Frsky_Backend::calc_nav_alt(void)
|
||||
|
||||
AP_AHRS &_ahrs = AP::ahrs();
|
||||
WITH_SEMAPHORE(_ahrs.get_semaphore());
|
||||
if (_ahrs.get_position(loc)) {
|
||||
if (_ahrs.get_location(loc)) {
|
||||
current_height = loc.alt*0.01f;
|
||||
if (!loc.relative_alt) {
|
||||
// loc.alt has home altitude added, remove it
|
||||
@ -109,7 +109,7 @@ void AP_Frsky_Backend::calc_gps_position(void)
|
||||
|
||||
Location loc;
|
||||
|
||||
if (_ahrs.get_position(loc)) {
|
||||
if (_ahrs.get_location(loc)) {
|
||||
float lat = format_gps(fabsf(loc.lat/10000000.0f));
|
||||
_SPort_data.latdddmm = lat;
|
||||
_SPort_data.latmmmm = (lat - _SPort_data.latdddmm) * 10000;
|
||||
|
@ -610,7 +610,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_home(void)
|
||||
{
|
||||
AP_AHRS &_ahrs = AP::ahrs();
|
||||
WITH_SEMAPHORE(_ahrs.get_semaphore());
|
||||
got_position = _ahrs.get_position(loc);
|
||||
got_position = _ahrs.get_location(loc);
|
||||
home_loc = _ahrs.get_home();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user