Skip to content

Commit

Permalink
AP_NavEKF3: To make decisions and flag settings clear
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed May 24, 2024
1 parent ead48b6 commit 65d7c0b
Showing 1 changed file with 12 additions and 36 deletions.
48 changes: 12 additions & 36 deletions libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -555,42 +555,18 @@ void NavEKF3_core::send_status_report(GCS_MAVLINK &link) const
{
// prepare flags
uint16_t flags = 0;
if (filterStatus.flags.attitude) {
flags |= EKF_ATTITUDE;
}
if (filterStatus.flags.horiz_vel) {
flags |= EKF_VELOCITY_HORIZ;
}
if (filterStatus.flags.vert_vel) {
flags |= EKF_VELOCITY_VERT;
}
if (filterStatus.flags.horiz_pos_rel) {
flags |= EKF_POS_HORIZ_REL;
}
if (filterStatus.flags.horiz_pos_abs) {
flags |= EKF_POS_HORIZ_ABS;
}
if (filterStatus.flags.vert_pos) {
flags |= EKF_POS_VERT_ABS;
}
if (filterStatus.flags.terrain_alt) {
flags |= EKF_POS_VERT_AGL;
}
if (filterStatus.flags.const_pos_mode) {
flags |= EKF_CONST_POS_MODE;
}
if (filterStatus.flags.pred_horiz_pos_rel) {
flags |= EKF_PRED_POS_HORIZ_REL;
}
if (filterStatus.flags.pred_horiz_pos_abs) {
flags |= EKF_PRED_POS_HORIZ_ABS;
}
if (!filterStatus.flags.initalized) {
flags |= EKF_UNINITIALIZED;
}
if (filterStatus.flags.gps_glitching) {
flags |= (1<<15);
}
if (filterStatus.flags.attitude) flags |= EKF_ATTITUDE;
if (filterStatus.flags.horiz_vel) flags |= EKF_VELOCITY_HORIZ;
if (filterStatus.flags.vert_vel) flags |= EKF_VELOCITY_VERT;
if (filterStatus.flags.horiz_pos_rel) flags |= EKF_POS_HORIZ_REL;
if (filterStatus.flags.horiz_pos_abs) flags |= EKF_POS_HORIZ_ABS;
if (filterStatus.flags.vert_pos) flags |= EKF_POS_VERT_ABS;
if (filterStatus.flags.terrain_alt) flags |= EKF_POS_VERT_AGL;
if (filterStatus.flags.const_pos_mode) flags |= EKF_CONST_POS_MODE;
if (filterStatus.flags.pred_horiz_pos_rel) flags |= EKF_PRED_POS_HORIZ_REL;
if (filterStatus.flags.pred_horiz_pos_abs) flags |= EKF_PRED_POS_HORIZ_ABS;
if (!filterStatus.flags.initalized) flags |= EKF_UNINITIALIZED;
if (filterStatus.flags.gps_glitching) flags |= (1<<15);

// get variances
float velVar = 0, posVar = 0, hgtVar = 0, tasVar = 0;
Expand Down

0 comments on commit 65d7c0b

Please sign in to comment.