AP_Compass: add and use AP_COMPASS_LSM9DS1_ENABLED
This commit is contained in:
parent
2ffe677d39
commit
fe9461242e
@ -426,7 +426,9 @@ private:
|
||||
#if AP_COMPASS_BMM150_ENABLED
|
||||
DRIVER_BMM150 =3,
|
||||
#endif
|
||||
#if AP_COMPASS_LSM9DS1_ENABLED
|
||||
DRIVER_LSM9DS1 =4,
|
||||
#endif
|
||||
DRIVER_LIS3MDL =5,
|
||||
DRIVER_AK09916 =6,
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
|
@ -1,13 +1,10 @@
|
||||
#include "AP_Compass_LSM9DS1.h"
|
||||
|
||||
#include <assert.h>
|
||||
#include <utility>
|
||||
#if AP_COMPASS_LSM9DS1_ENABLED
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_Compass_LSM9DS1.h"
|
||||
|
||||
|
||||
#define LSM9DS1M_OFFSET_X_REG_L_M 0x05
|
||||
#define LSM9DS1M_OFFSET_X_REG_H_M 0x06
|
||||
#define LSM9DS1M_OFFSET_Y_REG_L_M 0x07
|
||||
@ -234,3 +231,5 @@ void AP_Compass_LSM9DS1::_register_modify(uint8_t reg, uint8_t clearbits, uint8_
|
||||
val |= setbits;
|
||||
_register_write(reg, val);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -1,11 +1,14 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_Compass_config.h"
|
||||
|
||||
#if AP_COMPASS_LSM9DS1_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/Device.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "AP_Compass.h"
|
||||
#include "AP_Compass_Backend.h"
|
||||
|
||||
class AP_Compass_LSM9DS1 : public AP_Compass_Backend
|
||||
@ -40,3 +43,5 @@ private:
|
||||
float _scaling;
|
||||
enum Rotation _rotation;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -66,3 +66,7 @@
|
||||
#ifndef AP_COMPASS_LSM303D_ENABLED
|
||||
#define AP_COMPASS_LSM303D_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_LSM9DS1_ENABLED
|
||||
#define AP_COMPASS_LSM9DS1_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user