Blimp: INAV rename for neu & cm/cms

This commit is contained in:
Josh Henderson 2021-10-20 04:31:19 -04:00 committed by Andrew Tridgell
parent bdac4a2416
commit 119ed0c103
2 changed files with 3 additions and 3 deletions

View File

@ -69,7 +69,7 @@ bool AP_Arming_Blimp::barometer_checks(bool display_failure)
nav_filter_status filt_status = blimp.inertial_nav.get_filter_status(); nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs); bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
if (using_baro_ref) { if (using_baro_ref) {
if (fabsf(blimp.inertial_nav.get_altitude() - blimp.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) { if (fabsf(blimp.inertial_nav.get_position_z_up_cm() - blimp.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity"); check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");
ret = false; ret = false;
} }
@ -364,7 +364,7 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c
} }
// remember the height when we armed // remember the height when we armed
blimp.arming_altitude_m = blimp.inertial_nav.get_altitude() * 0.01; blimp.arming_altitude_m = blimp.inertial_nav.get_position_z_up_cm() * 0.01;
} }
hal.util->set_soft_armed(true); hal.util->set_soft_armed(true);

View File

@ -18,7 +18,7 @@ void Blimp::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_position_z_up_cm();
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 (!ahrs.home_is_set() || !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