1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/I2CDevice.h>
- #include <AP_Math/AP_Math.h>
- #include "AP_Compass.h"
- #include "AP_Compass_Backend.h"
- #ifndef HAL_COMPASS_QMC5883L_I2C_ADDR
- #define HAL_COMPASS_QMC5883L_I2C_ADDR 0x0D
- #endif
- #ifndef HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL
- #define HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL ROTATION_ROLL_180
- #endif
- #ifndef HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL
- #define HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL ROTATION_ROLL_180_YAW_270
- #endif
- class AP_Compass_QMC5883L : public AP_Compass_Backend
- {
- public:
- static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
- bool force_external,
- enum Rotation rotation);
- void read() override;
- static constexpr const char *name = "QMC5883L";
- private:
- AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
- bool force_external,
- enum Rotation rotation);
- void _dump_registers();
- bool _check_whoami();
- void timer();
- bool init();
- AP_HAL::OwnPtr<AP_HAL::Device> _dev;
- enum Rotation _rotation;
- uint8_t _instance;
- bool _force_external:1;
- };
|