mirror of https://github.com/ArduPilot/ardupilot
ArduSub: eliminate AP::ahrs().get_location
This commit is contained in:
parent
a38879f77e
commit
80a56a5fdf
|
@ -25,7 +25,7 @@ void Sub::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_location(temp_loc) && ahrs.get_origin(ekf_origin)) {
|
if (ahrs.get_position(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)) {
|
||||||
// ignore this failure
|
// ignore this failure
|
||||||
|
@ -38,7 +38,7 @@ bool Sub::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_location(temp_loc)) {
|
if (ahrs.get_position(temp_loc)) {
|
||||||
|
|
||||||
// Make home always at the water's surface.
|
// Make home always at the water's surface.
|
||||||
// This allows disarming and arming again at depth.
|
// This allows disarming and arming again at depth.
|
||||||
|
|
Loading…
Reference in New Issue