Browse Source

AP_InertialSensor: rename dataflash to logger

master
Tom Pittenger 6 years ago committed by Peter Barker
parent
commit
3eeaa2c8df
  1. 18
      libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp
  2. 14
      libraries/AP_InertialSensor/BatchSampler.cpp

18
libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp

@ -216,8 +216,8 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro) void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro)
{ {
AP_Logger *dataflash = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (dataflash == nullptr) { if (logger == nullptr) {
// should not have been called // should not have been called
return; return;
} }
@ -231,7 +231,7 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa
GyrY : gyro.y, GyrY : gyro.y,
GyrZ : gyro.z GyrZ : gyro.z
}; };
dataflash->WriteBlock(&pkt, sizeof(pkt)); logger->WriteBlock(&pkt, sizeof(pkt));
} else { } else {
if (!_imu.batchsampler.doing_sensor_rate_logging()) { if (!_imu.batchsampler.doing_sensor_rate_logging()) {
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro); _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro);
@ -348,8 +348,8 @@ void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t inst
void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel) void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel)
{ {
AP_Logger *dataflash = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (dataflash == nullptr) { if (logger == nullptr) {
// should not have been called // should not have been called
return; return;
} }
@ -363,7 +363,7 @@ void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t s
AccY : accel.y, AccY : accel.y,
AccZ : accel.z AccZ : accel.z
}; };
dataflash->WriteBlock(&pkt, sizeof(pkt)); logger->WriteBlock(&pkt, sizeof(pkt));
} else { } else {
if (!_imu.batchsampler.doing_sensor_rate_logging()) { if (!_imu.batchsampler.doing_sensor_rate_logging()) {
_imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, sample_us, accel); _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, sample_us, accel);
@ -465,11 +465,11 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const
// tracker does not set a bit // tracker does not set a bit
return false; return false;
} }
const AP_Logger *instance = AP_Logger::get_singleton(); const AP_Logger *logger = AP_Logger::get_singleton();
if (instance == nullptr) { if (logger == nullptr) {
return false; return false;
} }
if (!instance->should_log(_imu._log_raw_bit)) { if (!logger->should_log(_imu._log_raw_bit)) {
return false; return false;
} }
return true; return true;

14
libraries/AP_InertialSensor/BatchSampler.cpp

@ -176,8 +176,8 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
// avoid flooding AP_Logger's buffer // avoid flooding AP_Logger's buffer
return; return;
} }
AP_Logger *dataflash = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (dataflash == nullptr) { if (logger == nullptr) {
// should not have been called // should not have been called
return; return;
} }
@ -199,7 +199,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
} }
break; break;
} }
if (!dataflash->Write_ISBH(isb_seqnum, if (!logger->Write_ISBH(isb_seqnum,
type, type,
instance, instance,
multiplier, multiplier,
@ -212,7 +212,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
isbh_sent = true; isbh_sent = true;
} }
// pack and send a data packet: // pack and send a data packet:
if (!dataflash->Write_ISBD(isb_seqnum, if (!logger->Write_ISBD(isb_seqnum,
data_read_offset/samples_per_msg, data_read_offset/samples_per_msg,
&data_x[data_read_offset], &data_x[data_read_offset],
&data_y[data_read_offset], &data_y[data_read_offset],
@ -250,12 +250,12 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T
if (data_write_offset >= _required_count) { if (data_write_offset >= _required_count) {
return false; return false;
} }
AP_Logger *dataflash = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (dataflash == nullptr) { if (logger == nullptr) {
return false; return false;
} }
#define MASK_LOG_ANY 0xFFFF #define MASK_LOG_ANY 0xFFFF
if (!dataflash->should_log(MASK_LOG_ANY)) { if (!logger->should_log(MASK_LOG_ANY)) {
return false; return false;
} }
return true; return true;

Loading…
Cancel
Save