AP_InertialSensor: define AP_INERTIALSENSOR_ENABLED in a new AP_InertialSensor_config.h

This commit is contained in:
Peter Barker 2023-01-03 16:09:46 +11:00 committed by Andrew Tridgell
parent e8c5296087
commit 95527894de
3 changed files with 13 additions and 2 deletions

View File

@ -1,8 +1,11 @@
#include <assert.h> #include <assert.h>
#include "AP_InertialSensor.h"
#if AP_INERTIALSENSOR_ENABLED
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if AP_INERTIALSENSOR_ENABLED
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#include <AP_HAL/SPIDevice.h> #include <AP_HAL/SPIDevice.h>
#include <AP_HAL/DSP.h> #include <AP_HAL/DSP.h>
@ -19,7 +22,6 @@
#endif #endif
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_BMI160.h" #include "AP_InertialSensor_BMI160.h"
#include "AP_InertialSensor_BMI270.h" #include "AP_InertialSensor_BMI270.h"
#include "AP_InertialSensor_Backend.h" #include "AP_InertialSensor_Backend.h"

View File

@ -1,5 +1,7 @@
#pragma once #pragma once
#include "AP_InertialSensor_config.h"
// Gyro and Accelerometer calibration criteria // Gyro and Accelerometer calibration criteria
#define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f #define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
#define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f #define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f

View File

@ -0,0 +1,7 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_INERTIALSENSOR_ENABLED
#define AP_INERTIALSENSOR_ENABLED 1
#endif