AP_InertialSensor: fixed build with logging disabled

fixes CubeOrange-periph build
This commit is contained in:
Andrew Tridgell 2022-06-05 21:28:40 +10:00
parent 180c516b53
commit 19063a46a0
4 changed files with 12 additions and 1 deletions

View File

@ -418,6 +418,7 @@ void AP_InertialSensor_Backend::_notify_new_delta_angle(uint8_t instance, const
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)
{ {
#if HAL_LOGGING_ENABLED
AP_Logger *logger = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) { if (logger == nullptr) {
// should not have been called // should not have been called
@ -430,6 +431,7 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa
_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);
} }
} }
#endif
} }
/* /*
@ -631,6 +633,7 @@ 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)
{ {
#if HAL_LOGGING_ENABLED
AP_Logger *logger = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) { if (logger == nullptr) {
// should not have been called // should not have been called
@ -643,6 +646,7 @@ void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t s
_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);
} }
} }
#endif
} }
void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance, void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance,
@ -771,10 +775,12 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const
// log an unexpected change in a register for an IMU // log an unexpected change in a register for an IMU
void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg &reg) void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg &reg)
{ {
#if HAL_LOGGING_ENABLED
AP::logger().Write("IREG", "TimeUS,DevID,Bank,Reg,Val", "QIBBB", AP::logger().Write("IREG", "TimeUS,DevID,Bank,Reg,Val", "QIBBB",
AP_HAL::micros64(), AP_HAL::micros64(),
bus_id, bus_id,
reg.bank, reg.bank,
reg.regnum, reg.regnum,
reg.value); reg.value);
#endif
} }

View File

@ -759,7 +759,9 @@ check_registers:
events to help with log analysis, but don't shout at the events to help with log analysis, but don't shout at the
GCS to prevent possible flood GCS to prevent possible flood
*/ */
#if HAL_LOGGING_ENABLED
AP::logger().Write_MessageF("ICM20602 yofs fix: %x %x", y_ofs, _saved_y_ofs_high); AP::logger().Write_MessageF("ICM20602 yofs fix: %x %x", y_ofs, _saved_y_ofs_high);
#endif
_register_write(MPUREG_ACC_OFF_Y_H, _saved_y_ofs_high); _register_write(MPUREG_ACC_OFF_Y_H, _saved_y_ofs_high);
} }
} }

View File

@ -304,7 +304,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te
} }
const float tdiff = T - TEMP_REFERENCE; const float tdiff = T - TEMP_REFERENCE;
#if HAL_LOGGING_ENABLED
AP::logger().Write("TCLR", "TimeUS,I,SType,Temp,X,Y,Z,NSamp", AP::logger().Write("TCLR", "TimeUS,I,SType,Temp,X,Y,Z,NSamp",
"s#------", "s#------",
"F000000-", "F000000-",
@ -315,6 +315,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te
T, T,
st.sum.x, st.sum.y, st.sum.z, st.sum.x, st.sum.y, st.sum.z,
st.sum_count); st.sum_count);
#endif
st.pfit.update(tdiff, st.sum); st.pfit.update(tdiff, st.sum);

View File

@ -265,6 +265,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T
void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample) void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample)
{ {
#if HAL_LOGGING_ENABLED
if (!should_log(_instance, _type)) { if (!should_log(_instance, _type)) {
return; return;
} }
@ -277,5 +278,6 @@ void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSenso
data_z[data_write_offset] = multiplier*_sample.z; data_z[data_write_offset] = multiplier*_sample.z;
data_write_offset++; // may unblock the reading process data_write_offset++; // may unblock the reading process
#endif
} }
#endif //#if HAL_INS_ENABLED #endif //#if HAL_INS_ENABLED