Browse Source

AP_Frsky_Telem: rename AP_AHRS::get_position to get_location

gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
423bd1e8a4
  1. 4
      libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp
  2. 2
      libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp

4
libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp

@ -77,7 +77,7 @@ void AP_Frsky_Backend::calc_nav_alt(void) @@ -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) @@ -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;

2
libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp

@ -610,7 +610,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_home(void) @@ -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…
Cancel
Save