mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_InertialSensor: Post-filter logging takes precedence over sensor-rate logging.
This commit is contained in:
parent
52e4676564
commit
31ea3466af
@ -87,14 +87,15 @@ void AP_InertialSensor::BatchSampler::periodic()
|
||||
|
||||
void AP_InertialSensor::BatchSampler::update_doing_sensor_rate_logging()
|
||||
{
|
||||
if (((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_POST_FILTER)
|
||||
&& type == IMU_SENSOR_TYPE_GYRO) {
|
||||
// We can't do post-filter sensor rate logging
|
||||
if ((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_POST_FILTER) {
|
||||
_doing_post_filter_logging = true;
|
||||
_doing_sensor_rate_logging = false;
|
||||
return;
|
||||
}
|
||||
_doing_post_filter_logging = false;
|
||||
if (!((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_SENSOR_RATE)) {
|
||||
_doing_sensor_rate_logging = false;
|
||||
_doing_post_filter_logging = false;
|
||||
return;
|
||||
}
|
||||
const uint8_t bit = (1<<instance);
|
||||
|
Loading…
Reference in New Issue
Block a user