|
|
|
@ -24,8 +24,8 @@ const AP_Param::GroupInfo AP_InertialSensor::BatchSampler::var_info[] = {
@@ -24,8 +24,8 @@ const AP_Param::GroupInfo AP_InertialSensor::BatchSampler::var_info[] = {
|
|
|
|
|
|
|
|
|
|
// @Param: BAT_OPT
|
|
|
|
|
// @DisplayName: Batch Logging Options Mask
|
|
|
|
|
// @Description: Options for the BatchSampler. Post-filter and sensor-rate logging cannot be used at the same time.
|
|
|
|
|
// @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP), 1: Sample post-filtering
|
|
|
|
|
// @Description: Options for the BatchSampler.
|
|
|
|
|
// @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP), 1: Sample post-filtering, 2: Sample pre- and post-filter
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("BAT_OPT", 3, AP_InertialSensor::BatchSampler, _batch_options_mask, 0), |
|
|
|
|
|
|
|
|
@ -90,14 +90,13 @@ void AP_InertialSensor::BatchSampler::periodic()
@@ -90,14 +90,13 @@ void AP_InertialSensor::BatchSampler::periodic()
|
|
|
|
|
|
|
|
|
|
void AP_InertialSensor::BatchSampler::update_doing_sensor_rate_logging() |
|
|
|
|
{ |
|
|
|
|
// We can't do post-filter sensor rate logging
|
|
|
|
|
if ((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_POST_FILTER) { |
|
|
|
|
if (has_option(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)) { |
|
|
|
|
if (has_option(BATCH_OPT_PRE_POST_FILTER)) { |
|
|
|
|
_doing_pre_post_filter_logging = true; |
|
|
|
|
} |
|
|
|
|
if (!has_option(BATCH_OPT_SENSOR_RATE)) { |
|
|
|
|
_doing_sensor_rate_logging = false; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
@ -121,6 +120,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
@@ -121,6 +120,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
|
|
|
|
|
if ((1U<<instance) > (uint8_t)_sensor_mask) { |
|
|
|
|
// should only ever happen if user resets _sensor_mask
|
|
|
|
|
instance = 0; |
|
|
|
|
post_filter = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (type == IMU_SENSOR_TYPE_ACCEL) { |
|
|
|
@ -154,6 +154,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
@@ -154,6 +154,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
|
|
|
|
|
if (_sensor_mask & (1U<<i)) { |
|
|
|
|
instance = i; |
|
|
|
|
haveinstance = true; |
|
|
|
|
post_filter = !post_filter; |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -164,6 +165,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
@@ -164,6 +165,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
|
|
|
|
|
abort(); |
|
|
|
|
#endif |
|
|
|
|
instance = 0; |
|
|
|
|
post_filter = false; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|