mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_InertialSensor: define AP_INERTIALSENSOR_ENABLED in a new AP_InertialSensor_config.h
This commit is contained in:
parent
e8c5296087
commit
95527894de
@ -1,8 +1,11 @@
|
||||
#include <assert.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include <AP_HAL/SPIDevice.h>
|
||||
#include <AP_HAL/DSP.h>
|
||||
@ -19,7 +22,6 @@
|
||||
#endif
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#include "AP_InertialSensor.h"
|
||||
#include "AP_InertialSensor_BMI160.h"
|
||||
#include "AP_InertialSensor_BMI270.h"
|
||||
#include "AP_InertialSensor_Backend.h"
|
||||
|
@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_InertialSensor_config.h"
|
||||
|
||||
// Gyro and Accelerometer calibration criteria
|
||||
#define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
|
||||
#define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f
|
||||
|
7
libraries/AP_InertialSensor/AP_InertialSensor_config.h
Normal file
7
libraries/AP_InertialSensor/AP_InertialSensor_config.h
Normal file
@ -0,0 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_INERTIALSENSOR_ENABLED
|
||||
#define AP_INERTIALSENSOR_ENABLED 1
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user