mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_InertialSensor: rename dataflash to logger
This commit is contained in:
parent
12c3446777
commit
3eeaa2c8df
@ -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)
|
||||
{
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
}
|
||||
@ -231,7 +231,7 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa
|
||||
GyrY : gyro.y,
|
||||
GyrZ : gyro.z
|
||||
};
|
||||
dataflash->WriteBlock(&pkt, sizeof(pkt));
|
||||
logger->WriteBlock(&pkt, sizeof(pkt));
|
||||
} else {
|
||||
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
||||
_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)
|
||||
{
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
}
|
||||
@ -363,7 +363,7 @@ void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t s
|
||||
AccY : accel.y,
|
||||
AccZ : accel.z
|
||||
};
|
||||
dataflash->WriteBlock(&pkt, sizeof(pkt));
|
||||
logger->WriteBlock(&pkt, sizeof(pkt));
|
||||
} else {
|
||||
if (!_imu.batchsampler.doing_sensor_rate_logging()) {
|
||||
_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
|
||||
return false;
|
||||
}
|
||||
const AP_Logger *instance = AP_Logger::get_singleton();
|
||||
if (instance == nullptr) {
|
||||
const AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
return false;
|
||||
}
|
||||
if (!instance->should_log(_imu._log_raw_bit)) {
|
||||
if (!logger->should_log(_imu._log_raw_bit)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -176,8 +176,8 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
||||
// avoid flooding AP_Logger's buffer
|
||||
return;
|
||||
}
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
}
|
||||
@ -199,7 +199,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
||||
}
|
||||
break;
|
||||
}
|
||||
if (!dataflash->Write_ISBH(isb_seqnum,
|
||||
if (!logger->Write_ISBH(isb_seqnum,
|
||||
type,
|
||||
instance,
|
||||
multiplier,
|
||||
@ -212,7 +212,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
||||
isbh_sent = true;
|
||||
}
|
||||
// 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_x[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) {
|
||||
return false;
|
||||
}
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger == nullptr) {
|
||||
return false;
|
||||
}
|
||||
#define MASK_LOG_ANY 0xFFFF
|
||||
if (!dataflash->should_log(MASK_LOG_ANY)) {
|
||||
if (!logger->should_log(MASK_LOG_ANY)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user