AP_InertialSensor: inline vector ops for backends and temp cal

This commit is contained in:
Andy Piper 2021-11-25 20:05:40 +00:00 committed by Andrew Tridgell
parent dbcc8215fa
commit 6e3b502110
3 changed files with 6 additions and 1 deletions

View File

@ -1,3 +1,5 @@
#define AP_INLINE_VECTOR_OPS
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_Backend.h"

View File

@ -16,6 +16,7 @@
driver for all supported Invensense IMUs, including
MPU6000, MPU9250, ICM20608, ICM20602, ICM20601, ICM20789, ICM20689
*/
#define AP_INLINE_VECTOR_OPS
#include <assert.h>
#include <utility>
@ -422,6 +423,7 @@ bool AP_InertialSensor_Invensense::get_output_banner(char* banner, uint8_t banne
return false;
}
/*
publish any pending data
*/

View File

@ -16,10 +16,11 @@
IMU temperature calibration handling
*/
#define AP_INLINE_VECTOR_OPS
#include "AP_InertialSensor.h"
#if HAL_INS_TEMPERATURE_CAL_ENABLE
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Common/ExpandingString.h>