@@ -142,16 +142,21 @@ bool Blimp::ekf_has_absolute_position() const
142
142
return false ;
143
143
}
144
144
145
- // with EKF use filter status and ekf check
146
- nav_filter_status filt_status = inertial_nav.get_filter_status ();
147
-
148
145
// if disarmed we accept a predicted horizontal position
149
146
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 ;
154
154
}
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);
155
160
}
156
161
157
162
// 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
168
173
return false ;
169
174
}
170
175
171
- // get filter status from EKF
172
- nav_filter_status filt_status = inertial_nav.get_filter_status ();
173
-
174
176
// if disarmed we accept a predicted horizontal relative position
175
177
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);
179
179
}
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);
180
184
}
181
185
182
186
// 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
187
191
return false ;
188
192
}
189
193
190
- // with EKF use filter status and ekf check
191
- nav_filter_status filt_status = inertial_nav.get_filter_status ();
192
-
193
194
// 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 ;
195
203
}
196
204
197
205
// update_auto_armed - update status of auto_armed flag
0 commit comments