Copter: avoid SITL failure when changing current_loc.alt frame
This change avoids a SITL failure caused by an attempt to change current_loc.alt's frame when current_loc is 0,0,0
This commit is contained in:
parent
70311382d9
commit
c7f8c6155b
@ -20,7 +20,7 @@ void Copter::read_inertia()
|
|||||||
// current_loc.alt is alt-above-home, converted from inertial nav's alt-above-ekf-origin
|
// 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_altitude();
|
const int32_t alt_above_origin_cm = inertial_nav.get_altitude();
|
||||||
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_ORIGIN);
|
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_ORIGIN);
|
||||||
if (!current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
|
if (!ahrs.home_is_set() || !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
|
// 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);
|
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_HOME);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user