mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
d89d8ee564
commit
6a897f01d8
|
@ -1,6 +1,7 @@
|
|||
#define AP_INLINE_VECTOR_OPS
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
@ -816,6 +817,7 @@ void AP_InertialSensor_Backend::update_accel(uint8_t instance) /* front end */
|
|||
}
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
bool AP_InertialSensor_Backend::should_log_imu_raw() const
|
||||
{
|
||||
if (_imu._log_raw_bit == (uint32_t)-1) {
|
||||
|
@ -831,6 +833,7 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const
|
|||
}
|
||||
return true;
|
||||
}
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
// 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 ®)
|
||||
|
|
|
@ -312,7 +312,7 @@ protected:
|
|||
*/
|
||||
void notify_accel_fifo_reset(uint8_t instance) __RAMFUNC__;
|
||||
void notify_gyro_fifo_reset(uint8_t instance) __RAMFUNC__;
|
||||
|
||||
|
||||
// log an unexpected change in a register for an IMU
|
||||
void log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®) __RAMFUNC__;
|
||||
|
||||
|
|
|
@ -1,3 +1,7 @@
|
|||
#include <AP_Logger/AP_Logger_config.h>
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
||||
|
@ -188,3 +192,5 @@ void AP_InertialSensor::write_notch_log_messages() const
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
// this scale factor ensures params are easy to work with in GUI parameter editors
|
||||
#define SCALE_FACTOR 1.0e6
|
||||
|
|
Loading…
Reference in New Issue