From 19063a46a0c47bb0336cd7b87fa3acba8b895502 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 5 Jun 2022 21:28:40 +1000 Subject: [PATCH] AP_InertialSensor: fixed build with logging disabled fixes CubeOrange-periph build --- libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp | 6 ++++++ .../AP_InertialSensor/AP_InertialSensor_Invensense.cpp | 2 ++ libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp | 3 ++- libraries/AP_InertialSensor/BatchSampler.cpp | 2 ++ 4 files changed, 12 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index e1c2d89aa8..1f2ecd417e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -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) { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { // 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); } } +#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) { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { // 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); } } +#endif } 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 void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®) { +#if HAL_LOGGING_ENABLED AP::logger().Write("IREG", "TimeUS,DevID,Bank,Reg,Val", "QIBBB", AP_HAL::micros64(), bus_id, reg.bank, reg.regnum, reg.value); +#endif } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp index 354be1eda5..8800bb024d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp @@ -759,7 +759,9 @@ check_registers: events to help with log analysis, but don't shout at the GCS to prevent possible flood */ +#if HAL_LOGGING_ENABLED 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); } } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index 1ddb8d9b7c..fd3d37b26a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -304,7 +304,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te } const float tdiff = T - TEMP_REFERENCE; - +#if HAL_LOGGING_ENABLED AP::logger().Write("TCLR", "TimeUS,I,SType,Temp,X,Y,Z,NSamp", "s#------", "F000000-", @@ -315,6 +315,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te T, st.sum.x, st.sum.y, st.sum.z, st.sum_count); +#endif st.pfit.update(tdiff, st.sum); diff --git a/libraries/AP_InertialSensor/BatchSampler.cpp b/libraries/AP_InertialSensor/BatchSampler.cpp index b6e8ac72af..77d741bc7b 100644 --- a/libraries/AP_InertialSensor/BatchSampler.cpp +++ b/libraries/AP_InertialSensor/BatchSampler.cpp @@ -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) { +#if HAL_LOGGING_ENABLED if (!should_log(_instance, _type)) { return; } @@ -277,5 +278,6 @@ void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSenso data_z[data_write_offset] = multiplier*_sample.z; data_write_offset++; // may unblock the reading process +#endif } #endif //#if HAL_INS_ENABLED