AP_InertialSensor: use DataFlash should_log to determine raw logging
This commit is contained in:
parent
075c40bd60
commit
6ae86a0b8c
@ -443,7 +443,7 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
_primary_accel(0),
|
||||
_hil_mode(false),
|
||||
_calibrating(false),
|
||||
_log_raw_data(false),
|
||||
_log_raw_bit(-1),
|
||||
_backends_detected(false),
|
||||
_dataflash(nullptr),
|
||||
_accel_cal_requires_reboot(false),
|
||||
|
@ -201,11 +201,8 @@ public:
|
||||
// get the accel filter rate in Hz
|
||||
uint8_t get_accel_filter_hz(void) const { return _accel_filter_cutoff; }
|
||||
|
||||
// pass in a pointer to DataFlash for raw data logging
|
||||
void set_dataflash(DataFlash_Class *dataflash) { _dataflash = dataflash; }
|
||||
|
||||
// enable/disable raw gyro/accel logging
|
||||
void set_raw_logging(bool enable) { _log_raw_data = enable; }
|
||||
// indicate which bit in LOG_BITMASK indicates raw logging enabled
|
||||
void set_log_raw_bit(uint32_t log_raw_bit) { _log_raw_bit = log_raw_bit; }
|
||||
|
||||
// calculate vibration levels and check for accelerometer clipping (called by a backends)
|
||||
void calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt);
|
||||
@ -393,6 +390,9 @@ private:
|
||||
uint8_t _primary_gyro;
|
||||
uint8_t _primary_accel;
|
||||
|
||||
// bitmask bit which indicates if we should log raw accel and gyro data
|
||||
uint32_t _log_raw_bit;
|
||||
|
||||
// has wait_for_sample() found a sample?
|
||||
bool _have_sample:1;
|
||||
|
||||
@ -402,9 +402,6 @@ private:
|
||||
// are gyros or accels currently being calibrated
|
||||
bool _calibrating:1;
|
||||
|
||||
// should we log raw accel/gyro data?
|
||||
bool _log_raw_data:1;
|
||||
|
||||
bool _backends_detected:1;
|
||||
|
||||
// the delta time in seconds for the last sample
|
||||
|
@ -409,3 +409,19 @@ void AP_InertialSensor_Backend::update_accel(uint8_t instance)
|
||||
|
||||
_sem->give();
|
||||
}
|
||||
|
||||
DataFlash_Class *AP_InertialSensor_Backend::get_dataflash() const
|
||||
{
|
||||
DataFlash_Class *instance = DataFlash_Class::instance();
|
||||
if (instance == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (_imu._log_raw_bit == (uint32_t)-1) {
|
||||
// tracker does not set a bit
|
||||
return nullptr;
|
||||
}
|
||||
if (!instance->should_log(_imu._log_raw_bit)) {
|
||||
return nullptr;
|
||||
}
|
||||
return instance;
|
||||
}
|
||||
|
@ -174,10 +174,9 @@ protected:
|
||||
// return the requested sample rate in Hz
|
||||
uint16_t get_sample_rate_hz(void) const;
|
||||
|
||||
// access to frontend dataflash
|
||||
DataFlash_Class *get_dataflash(void) const {
|
||||
return _imu._log_raw_data? _imu._dataflash : nullptr;
|
||||
}
|
||||
// access to frontend dataflash. If raw-imu logging is not
|
||||
// enabled, nullptr is returned
|
||||
DataFlash_Class *get_dataflash() const;
|
||||
|
||||
// common gyro update function for all backends
|
||||
void update_gyro(uint8_t instance);
|
||||
|
Loading…
Reference in New Issue
Block a user