mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
attitude_estimator_q: don't spam console
We should not spam the console just because the input data is degenerate, it would only make things worse because everything would slow down due to the printfs.
This commit is contained in:
@@ -355,7 +355,7 @@ void AttitudeEstimatorQ::task_main()
|
||||
_accel(2) = _lp_accel_z.apply(sensors.accelerometer_m_s2[2]);
|
||||
|
||||
if (_accel.length() < 0.01f) {
|
||||
warnx("WARNING: degenerate accel!");
|
||||
PX4_DEBUG("WARNING: degenerate accel!");
|
||||
continue;
|
||||
}
|
||||
}
|
||||
@@ -366,7 +366,7 @@ void AttitudeEstimatorQ::task_main()
|
||||
_mag(2) = sensors.magnetometer_ga[2];
|
||||
|
||||
if (_mag.length() < 0.01f) {
|
||||
warnx("WARNING: degenerate mag!");
|
||||
PX4_DEBUG("WARNING: degenerate mag!");
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user