Skip to content

Commit a43049d

Browse files
committed
Blimp: remove get_filter_status from AP_InertialNav
1 parent 876e9a9 commit a43049d

File tree

4 files changed

+30
-26
lines changed

4 files changed

+30
-26
lines changed

Blimp/AP_Arming_Blimp.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,8 @@ bool AP_Arming_Blimp::barometer_checks(bool display_failure)
5959
// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
6060
// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
6161
// that may differ from the baro height due to baro drift.
62-
nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();
63-
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
62+
const auto &ahrs = AP::ahrs();
63+
const bool using_baro_ref = !ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_REL) && ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_ABS);
6464
if (using_baro_ref) {
6565
if (fabsf(blimp.inertial_nav.get_position_z_up_cm() - blimp.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
6666
check_failed(Check::BARO, display_failure, "Altitude disparity");
@@ -195,10 +195,7 @@ bool AP_Arming_Blimp::gps_checks(bool display_failure)
195195
// check ekf attitude is acceptable
196196
bool AP_Arming_Blimp::pre_arm_ekf_attitude_check()
197197
{
198-
// get ekf filter status
199-
nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();
200-
201-
return filt_status.flags.attitude;
198+
return AP::ahrs().has_status(AP_AHRS::Status::ATTITUDE_VALID);
202199
}
203200

204201
// performs mandatory gps checks. returns true if passed

Blimp/events.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -161,8 +161,7 @@ void Blimp::do_failsafe_action(Failsafe_Action action, ModeReason reason)
161161
void Blimp::gpsglitch_check()
162162
{
163163
// get filter status
164-
nav_filter_status filt_status = inertial_nav.get_filter_status();
165-
bool gps_glitching = filt_status.flags.gps_glitching;
164+
const bool gps_glitching = AP::ahrs().has_status(AP_AHRS::Status::GPS_GLITCHING);
166165

167166
// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS
168167
if (ap.gps_glitching != gps_glitching) {

Blimp/inertia.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ void Blimp::read_inertia()
1313
current_loc.lng = loc.lng;
1414

1515
// exit immediately if we do not have an altitude estimate
16-
if (!inertial_nav.get_filter_status().flags.vert_pos) {
16+
if (!ahrs.has_status(AP_AHRS::Status::VERT_POS)) {
1717
return;
1818
}
1919

Blimp/system.cpp

Lines changed: 25 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -142,16 +142,21 @@ bool Blimp::ekf_has_absolute_position() const
142142
return false;
143143
}
144144

145-
// with EKF use filter status and ekf check
146-
nav_filter_status filt_status = inertial_nav.get_filter_status();
147-
148145
// if disarmed we accept a predicted horizontal position
149146
if (!motors->armed()) {
150-
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
151-
} else {
152-
// once armed we require a good absolute position and EKF must not be in const_pos_mode
153-
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
147+
if (ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS)) {
148+
return true;
149+
}
150+
if (ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_ABS)) {
151+
return true;
152+
}
153+
return false;
154154
}
155+
// once armed we require a good absolute position and EKF must not be in const_pos_mode
156+
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
157+
return false;
158+
}
159+
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS);
155160
}
156161

157162
// ekf_has_relative_position - returns true if the EKF can provide a position estimate relative to it's starting position
@@ -168,15 +173,14 @@ bool Blimp::ekf_has_relative_position() const
168173
return false;
169174
}
170175

171-
// get filter status from EKF
172-
nav_filter_status filt_status = inertial_nav.get_filter_status();
173-
174176
// if disarmed we accept a predicted horizontal relative position
175177
if (!motors->armed()) {
176-
return (filt_status.flags.pred_horiz_pos_rel);
177-
} else {
178-
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
178+
return ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_REL);
179179
}
180+
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
181+
return false;
182+
}
183+
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_REL);
180184
}
181185

182186
// returns true if the ekf has a good altitude estimate (required for modes which do AltHold)
@@ -187,11 +191,15 @@ bool Blimp::ekf_alt_ok() const
187191
return false;
188192
}
189193

190-
// with EKF use filter status and ekf check
191-
nav_filter_status filt_status = inertial_nav.get_filter_status();
192-
193194
// require both vertical velocity and position
194-
return (filt_status.flags.vert_vel && filt_status.flags.vert_pos);
195+
if (!ahrs.has_status(AP_AHRS::Status::VERT_VEL)) {
196+
return false;
197+
}
198+
if (!ahrs.has_status(AP_AHRS::Status::VERT_POS)) {
199+
return false;
200+
}
201+
202+
return true;
195203
}
196204

197205
// update_auto_armed - update status of auto_armed flag

0 commit comments

Comments
 (0)