AP_NavEKF2: change priority of statustext messages

This commit is contained in:
Jonathan Challinger 2016-07-28 14:25:07 -07:00 committed by Randy Mackay
parent 9666b1478a
commit d1ecc63bf1
2 changed files with 7 additions and 7 deletions

View File

@ -239,7 +239,7 @@ void NavEKF2_core::setAidingMode()
stateStruct.position.z = -meaHgtAtTakeOff;
} else if (PV_AidingMode == AID_RELATIVE) {
// We have commenced aiding, but GPS usage has been prohibited so use optical flow only
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u is using optical flow",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u is using optical flow",(unsigned)imu_index);
posTimeout = true;
velTimeout = true;
// Reset the last valid flow measurement time
@ -248,7 +248,7 @@ void NavEKF2_core::setAidingMode()
prevFlowFuseTime_ms = imuSampleTime_ms;
} else if (PV_AidingMode == AID_ABSOLUTE) {
// We have commenced aiding and GPS usage is allowed
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u is using GPS",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u is using GPS",(unsigned)imu_index);
posTimeout = false;
velTimeout = false;
// we need to reset the GPS timers to prevent GPS timeout logic being invoked on entry into GPS aiding
@ -277,7 +277,7 @@ void NavEKF2_core::checkAttitudeAlignmentStatus()
tiltErrFilt = alpha*temp + (1.0f-alpha)*tiltErrFilt;
if (tiltErrFilt < 0.005f && !tiltAlignComplete) {
tiltAlignComplete = true;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
}
// submit yaw and magnetic field reset requests depending on whether we have compass data
@ -353,7 +353,7 @@ void NavEKF2_core::setOrigin()
// define Earth rotation vector in the NED navigation frame at the origin
calcEarthRateNED(earthRateNED, _ahrs->get_home().lat);
validOrigin = true;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u Origin Set",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u Origin Set",(unsigned)imu_index);
}
// record a yaw reset event

View File

@ -113,12 +113,12 @@ void NavEKF2_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u initial yaw alignment complete",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u initial yaw alignment complete",(unsigned)imu_index);
}
// send in-flight yaw alignment status to console
if (finalResetRequest) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
} else if (interimResetRequest) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
}
@ -170,7 +170,7 @@ void NavEKF2_core::realignYawGPS()
ResetPosition();
// send yaw alignment information to console
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "EKF2 IMU%u yaw aligned to GPS velocity",(unsigned)imu_index);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF2 IMU%u yaw aligned to GPS velocity",(unsigned)imu_index);
// zero the attitude covariances becasue the corelations will now be invalid
zeroAttCovOnly();