mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: remove redundant check for home-is-set
this is done as part of the frame change
This commit is contained in:
parent
d1a1bcba19
commit
1eefb4923c
|
@ -20,7 +20,7 @@ void Copter::read_inertia()
|
|||
// current_loc.alt is alt-above-home, converted from inertial nav's alt-above-ekf-origin
|
||||
const int32_t alt_above_origin_cm = inertial_nav.get_position_z_up_cm();
|
||||
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_ORIGIN);
|
||||
if (!ahrs.home_is_set() || !current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
|
||||
if (current_loc.initialised() && !current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
|
||||
// if home has not been set yet we treat alt-above-origin as alt-above-home
|
||||
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_HOME);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue