mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: removed default rotations for compass probe
this prevents bugs where the force_external and rotation are mixed up in hwdef.dat causing incorrect rotations
This commit is contained in:
parent
2a48241ebb
commit
f877def909
@ -42,17 +42,17 @@ public:
|
|||||||
/* Probe for AK09916 standalone on I2C bus */
|
/* Probe for AK09916 standalone on I2C bus */
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
||||||
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI */
|
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI */
|
||||||
static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance,
|
static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "AK09916";
|
static constexpr const char *name = "AK09916";
|
||||||
|
|
||||||
@ -62,7 +62,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,
|
AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
|
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
|
||||||
|
@ -19,15 +19,15 @@ class AP_Compass_AK8963 : public AP_Compass_Backend
|
|||||||
public:
|
public:
|
||||||
/* Probe for AK8963 standalone on I2C bus */
|
/* Probe for AK8963 standalone on I2C bus */
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
|
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
|
||||||
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
|
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
|
||||||
static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,
|
static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "AK8963";
|
static constexpr const char *name = "AK8963";
|
||||||
|
|
||||||
@ -37,7 +37,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
|
AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
|
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
|
||||||
|
@ -17,10 +17,10 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation = ROTATION_NONE);
|
static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "HMC5843";
|
static constexpr const char *name = "HMC5843";
|
||||||
|
|
||||||
|
@ -32,8 +32,8 @@ class AP_Compass_IST8308 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
@ -32,8 +32,8 @@ class AP_Compass_IST8310 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
@ -34,8 +34,8 @@ class AP_Compass_LIS3MDL : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
@ -12,7 +12,7 @@ class AP_Compass_LSM303D : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
enum Rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "LSM303D";
|
static constexpr const char *name = "LSM303D";
|
||||||
|
|
||||||
|
@ -12,7 +12,7 @@ class AP_Compass_LSM9DS1 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "LSM9DS1";
|
static constexpr const char *name = "LSM9DS1";
|
||||||
|
|
||||||
@ -22,7 +22,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
bool init();
|
bool init();
|
||||||
bool _check_id(void);
|
bool _check_id(void);
|
||||||
bool _configure(void);
|
bool _configure(void);
|
||||||
|
@ -17,7 +17,7 @@ class AP_Compass_MAG3110 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
enum Rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
static constexpr const char *name = "MAG3110";
|
static constexpr const char *name = "MAG3110";
|
||||||
|
|
||||||
|
@ -30,8 +30,8 @@ class AP_Compass_MMC3416 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
@ -44,7 +44,7 @@ class AP_Compass_QMC5883L : public AP_Compass_Backend
|
|||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
@ -30,8 +30,8 @@ class AP_Compass_RM3100 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
bool force_external = false,
|
bool force_external,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation);
|
||||||
|
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user