Browse Source

AP_InertialSensor: Post-filter logging takes precedence over sensor-rate logging.

master
Andy Piper 6 years ago committed by Andrew Tridgell
parent
commit
31ea3466af
  1. 7
      libraries/AP_InertialSensor/BatchSampler.cpp

7
libraries/AP_InertialSensor/BatchSampler.cpp

@ -87,14 +87,15 @@ void AP_InertialSensor::BatchSampler::periodic() @@ -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…
Cancel
Save