mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: add and use AP_COMPASS_RM3100_ENABLED
This commit is contained in:
parent
aa7932e65a
commit
69bc24bc16
|
@ -1228,7 +1228,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||||
#endif
|
#endif
|
||||||
#endif // AP_COMPASS_MMC3416_ENABLED
|
#endif // AP_COMPASS_MMC3416_ENABLED
|
||||||
|
|
||||||
#if AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED || defined(HAL_USE_I2C_MAG_RM3100)
|
#if AP_COMPASS_RM3100_ENABLED
|
||||||
#ifdef HAL_COMPASS_RM3100_I2C_ADDR
|
#ifdef HAL_COMPASS_RM3100_I2C_ADDR
|
||||||
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };
|
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };
|
||||||
#else
|
#else
|
||||||
|
@ -1252,7 +1252,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif // AP_COMPASS_RM3100_ENABLED
|
||||||
|
|
||||||
#if AP_COMPASS_BMM150_DETECT_BACKENDS_ENABLED
|
#if AP_COMPASS_BMM150_DETECT_BACKENDS_ENABLED
|
||||||
// BMM150 on I2C
|
// BMM150 on I2C
|
||||||
|
|
|
@ -459,7 +459,9 @@ private:
|
||||||
#if AP_COMPASS_IST8308_ENABLED
|
#if AP_COMPASS_IST8308_ENABLED
|
||||||
DRIVER_IST8308 =15,
|
DRIVER_IST8308 =15,
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_COMPASS_RM3100_ENABLED
|
||||||
DRIVER_RM3100 =16,
|
DRIVER_RM3100 =16,
|
||||||
|
#endif
|
||||||
#if AP_COMPASS_MSP_ENABLED
|
#if AP_COMPASS_MSP_ENABLED
|
||||||
DRIVER_MSP =17,
|
DRIVER_MSP =17,
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -19,6 +19,8 @@
|
||||||
*/
|
*/
|
||||||
#include "AP_Compass_RM3100.h"
|
#include "AP_Compass_RM3100.h"
|
||||||
|
|
||||||
|
#if AP_COMPASS_RM3100_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
@ -242,3 +244,5 @@ void AP_Compass_RM3100::read()
|
||||||
{
|
{
|
||||||
drain_accumulated_samples(compass_instance);
|
drain_accumulated_samples(compass_instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_COMPASS_RM3100_ENABLED
|
||||||
|
|
|
@ -14,6 +14,10 @@
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Compass_config.h"
|
||||||
|
|
||||||
|
#if AP_COMPASS_RM3100_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>
|
||||||
#include <AP_HAL/Device.h>
|
#include <AP_HAL/Device.h>
|
||||||
|
@ -58,3 +62,5 @@ private:
|
||||||
enum Rotation rotation;
|
enum Rotation rotation;
|
||||||
float _scaler = 1.0;
|
float _scaler = 1.0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_COMPASS_RM3100_ENABLED
|
||||||
|
|
|
@ -94,3 +94,7 @@
|
||||||
#ifndef AP_COMPASS_QMC5883L_ENABLED
|
#ifndef AP_COMPASS_QMC5883L_ENABLED
|
||||||
#define AP_COMPASS_QMC5883L_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
#define AP_COMPASS_QMC5883L_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_COMPASS_RM3100_ENABLED
|
||||||
|
#define AP_COMPASS_RM3100_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue