mirror of https://github.com/ArduPilot/ardupilot
37 lines
1.7 KiB
C++
37 lines
1.7 KiB
C++
#ifndef AP_Compass_HMC5883L_H
|
|
#define AP_Compass_HMC5883L_H
|
|
|
|
#include "../AP_Common/AP_Common.h"
|
|
#include "../AP_Math/AP_Math.h"
|
|
|
|
#include "Compass.h"
|
|
|
|
// orientations for DIYDrones magnetometer
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_FORWARD ROTATION_YAW_90
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_FORWARD_RIGHT ROTATION_YAW_135
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_RIGHT ROTATION_YAW_180
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_BACK_RIGHT ROTATION_YAW_225
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_BACK ROTATION_YAW_270
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_BACK_LEFT ROTATION_YAW_315
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_LEFT ROTATION_NONE
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_UP_PINS_FORWARD_LEFT ROTATION_YAW_45
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_FORWARD ROTATION_ROLL_180_YAW_270
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_FORWARD_RIGHT ROTATION_ROLL_180_YAW_315
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_RIGHT ROTATION_ROLL_180
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_BACK_RIGHT ROTATION_ROLL_180_YAW_45
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_BACK ROTATION_ROLL_180_YAW_90
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_BACK_LEFT ROTATION_ROLL_180_YAW_135
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_LEFT ROTATION_PITCH_180
|
|
#define AP_COMPASS_HMC5883L_COMPONENTS_DOWN_PINS_FORWARD_LEFT ROTATION_ROLL_180_YAW_225
|
|
|
|
class AP_Compass_HMC5883L : public Compass
|
|
{
|
|
private:
|
|
float calibration[3];
|
|
public:
|
|
AP_Compass_HMC5883L(AP_Var::Key key = AP_Var::k_key_none) : Compass(key) { product_id = AP_COMPASS_TYPE_HMC5883L; }
|
|
virtual bool init();
|
|
virtual void read();
|
|
};
|
|
#endif
|