mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: stop changing frame to home when home not set
This commit is contained in:
parent
08a18d6a0a
commit
17060d5d66
@ -15,13 +15,12 @@ void Copter::read_inertia()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
Location::AltFrame frame;
|
|
||||||
if (ahrs.home_is_set()) {
|
if (ahrs.home_is_set()) {
|
||||||
frame = Location::AltFrame::ABOVE_HOME;
|
current_loc.set_alt_cm(inertial_nav.get_altitude(),
|
||||||
|
Location::AltFrame::ABOVE_HOME);
|
||||||
} else {
|
} else {
|
||||||
// without home use alt above the EKF origin
|
// without home use alt above the EKF origin
|
||||||
frame = Location::AltFrame::ABOVE_ORIGIN;
|
current_loc.set_alt_cm(inertial_nav.get_altitude(),
|
||||||
|
Location::AltFrame::ABOVE_ORIGIN);
|
||||||
}
|
}
|
||||||
current_loc.set_alt_cm(inertial_nav.get_altitude(), frame);
|
|
||||||
current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME);
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user