mirror of https://github.com/ArduPilot/ardupilot
Blimp: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
4640ef9a66
commit
89b56f38f2
|
@ -25,7 +25,7 @@ void Blimp::set_home_to_current_location_inflight()
|
||||||
// get current location from EKF
|
// get current location from EKF
|
||||||
Location temp_loc;
|
Location temp_loc;
|
||||||
Location ekf_origin;
|
Location ekf_origin;
|
||||||
if (ahrs.get_position(temp_loc) && ahrs.get_origin(ekf_origin)) {
|
if (ahrs.get_location(temp_loc) && ahrs.get_origin(ekf_origin)) {
|
||||||
temp_loc.alt = ekf_origin.alt;
|
temp_loc.alt = ekf_origin.alt;
|
||||||
if (!set_home(temp_loc, false)) {
|
if (!set_home(temp_loc, false)) {
|
||||||
return;
|
return;
|
||||||
|
@ -38,7 +38,7 @@ bool Blimp::set_home_to_current_location(bool lock)
|
||||||
{
|
{
|
||||||
// get current location from EKF
|
// get current location from EKF
|
||||||
Location temp_loc;
|
Location temp_loc;
|
||||||
if (ahrs.get_position(temp_loc)) {
|
if (ahrs.get_location(temp_loc)) {
|
||||||
if (!set_home(temp_loc, lock)) {
|
if (!set_home(temp_loc, lock)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -8,7 +8,7 @@ void Blimp::read_inertia()
|
||||||
|
|
||||||
// pull position from ahrs
|
// pull position from ahrs
|
||||||
Location loc;
|
Location loc;
|
||||||
ahrs.get_position(loc);
|
ahrs.get_location(loc);
|
||||||
current_loc.lat = loc.lat;
|
current_loc.lat = loc.lat;
|
||||||
current_loc.lng = loc.lng;
|
current_loc.lng = loc.lng;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue