2 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX 30 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub) 31 #define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE 33 #define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL 36 #ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT 37 #define AP_COMPASS_OFFSETS_MAX_DEFAULT 850 40 #ifndef HAL_COMPASS_FILTER_DEFAULT 41 #define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default 455 _compass_cal_autoreboot(false),
456 _cal_complete_requires_reboot(false),
461 _custom_rotation(nullptr),
462 _null_init_done(false),
466 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 531 uint32_t mask = (1U<<uint8_t(driver_type));
542 if (
id == uint32_t(
_state[i].dev_id.get())) {
559 #if AP_FEATURE_BOARD_DETECT 570 #define ADD_BACKEND(driver_type, backend, name, external) \ 571 do { if (_driver_enabled(driver_type)) { _add_backend(backend, name, external); } \ 572 if (_backend_count == COMPASS_MAX_BACKEND || \ 573 _compass_count == COMPASS_MAX_INSTANCES) { \ 578 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 583 #if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL 585 #elif AP_FEATURE_BOARD_DETECT 618 #if !HAL_MINIMIZE_FEATURES 670 #endif // HAL_MINIMIZE_FEATURES 681 #ifdef HAL_COMPASS_IST8310_I2C_BUS 785 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH 789 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI 796 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE 802 "platform/80860F41:05",
804 "pci0000:00/0000:00:18.6" },
808 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2 815 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO 820 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_OCPOC_ZYNQ 825 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_EDGE 828 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \ 829 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ 830 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI 835 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE 840 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET 845 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250 848 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843 849 #ifndef HAL_COMPASS_HMC5843_ROTATION 850 # define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE 855 #if defined(HAL_COMPASS_HMC5843_I2C_EXT_BUS) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 859 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000 862 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C 865 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C 868 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AERO 875 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_LIS3MDL 878 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_MAG3110 881 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_IST8310 884 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L 891 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE 898 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BMM150_I2C 901 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE 904 #error Unrecognised HAL_COMPASS_TYPE setting 908 #if defined(BOARD_I2C_BUS_EXT) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 932 #ifdef HAL_COMPASS_BMM150_I2C_ADDR 945 #ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS 995 uint8_t healthy_mask = 0;
998 healthy_mask |= 1 << i;
1001 return healthy_mask;
1080 (
float)latitude / 10000000,
1081 (
float)longitude / 10000000)));
1106 if (save_to_eeprom) {
1125 float cos_pitch_sq = 1.0f-(dcm_matrix.
c.
x*dcm_matrix.
c.
x);
1130 float headY = field.
y * dcm_matrix.
c.
z - field.
z * dcm_matrix.
c.
y;
1133 float headX = field.
x * cos_pitch_sq - dcm_matrix.
c.
x * (field.
y * dcm_matrix.
c.
y + field.
z * dcm_matrix.
c.
z);
1144 heading -= (2.0f *
M_PI);
1145 else if (heading < -
M_PI)
1146 heading += (2.0f *
M_PI);
1175 if (
_state[i].dev_id != dev_id_orig) {
1188 bool all_configured =
true;
1192 return all_configured;
1215 _hil.field[instance].rotate(MAG_BOARD_ORIENTATION);
1220 if (!
_state[0].external) {
1228 _hil.healthy[instance] =
true;
1235 _hil.field[instance] = mag;
1236 _hil.healthy[instance] =
true;
1242 return _hil.field[instance];
1249 _hil.Bearth(400, 0, 0);
1277 if (!primary_mag_field.
is_zero()) {
1278 primary_mag_field_norm = primary_mag_field.
normalized();
1284 Vector2f primary_mag_field_xy_norm;
1286 if (!primary_mag_field_xy.
is_zero()) {
1287 primary_mag_field_xy_norm = primary_mag_field_xy.
normalized();
1306 if (!mag_field_xy.
is_zero()) {
1307 mag_field_xy_norm = mag_field_xy.
normalized();
1312 float xyz_ang_diff = acosf(
constrain_float(mag_field_norm * primary_mag_field_norm,-1.0
f,1.0
f));
1313 float xy_ang_diff = acosf(
constrain_float(mag_field_xy_norm*primary_mag_field_xy_norm,-1.0
f,1.0
f));
1314 float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();
1326 if (xyz_ang_diff_large || xy_ang_diff_large || xy_length_diff_large) {
static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype)
uint8_t register_compass(void)
AP_Int8 _auto_declination
#define HAL_COMPASS_ICM20948_I2C_ADDR
#define HAL_COMPASS_IST8310_I2C_ADDR
Vector2< float > Vector2f
static constexpr const char * name
#define COMPASS_LEARN_DEFAULT
#define AP_COMPASS_MAX_XYZ_ANG_DIFF
bool _have_driver(AP_HAL::Device::BusType bus_type, uint8_t bus_num, uint8_t address, uint8_t devtype) const
Vector3< float > Vector3f
#define AP_COMPASS_MOT_COMP_DISABLED
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
static enum px4_board_type get_board_type(void)
float get_declination() const
uint32_t last_update_usec
AP_Int32 _driver_type_mask
static Compass * get_singleton()
Vector3< T > normalized() const
static AP_Compass_Backend * detect(Compass &compass)
AP_HAL::UARTDriver * console
bool _driver_enabled(enum DriverType driver_type)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals)
static AP_Compass_Backend * probe(Compass &compass)
#define HAL_COMPASS_HMC5843_I2C_ADDR
const Vector3f & get_offsets(void) const
void setHIL(uint8_t instance, float roll, float pitch, float yaw)
#define HAL_INS_LSM9DS0_A_NAME
static constexpr const char * name
#define AP_COMPASS_OFFSETS_MAX_DEFAULT
#define AP_GROUPINFO(name, idx, clazz, element, def)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
static constexpr const char * name
#define HAL_COMPASS_LIS3MDL_I2C_ADDR
bool _add_backend(AP_Compass_Backend *backend, const char *name, bool external)
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
void from_euler(float roll, float pitch, float yaw)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
static constexpr const char * name
#define HAL_COMPASS_HMC5843_ROTATION
#define HAL_COMPASS_HMC5843_I2C_BUS
void set_offsets(uint8_t i, const Vector3f &offsets)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external, enum Rotation rotation=ROTATION_NONE)
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
uint8_t get_healthy_mask() const
void _setup_earth_field()
uint8_t get_primary(void) const
#define AP_COMPASS_MAX_XY_LENGTH_DIFF
float calculate_heading(const Matrix3f &dcm_matrix) const
virtual void delay(uint16_t ms)=0
void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
Vector2< T > normalized() const
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(std::vector< const char *> devpaths, uint8_t address) override
virtual void printf(const char *,...) FMT_PRINTF(2
virtual OwnPtr< SPIDevice > get_device(const char *name)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool is_zero(const T fVal1)
static constexpr const char * name
#define HAL_MAG3110_I2C_ADDR
#define HAL_COMPASS_FILTER_DEFAULT
static constexpr const char * name
static constexpr const char * name
AP_Compass_Backend * _backends[COMPASS_MAX_BACKEND]
#define AP_COMPASS_MAX_XY_ANG_DIFF
#define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT
#define HAL_INS_LSM9DS0_EXT_A_NAME
Vector3f field[COMPASS_MAX_INSTANCES]
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define HAL_COMPASS_LIS3MDL_I2C_ADDR2
AP_HAL::SPIDeviceManager * spi
const Vector3f & getHIL(uint8_t instance) const
#define HAL_COMPASS_AK09916_I2C_ADDR
void _detect_backends(void)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
AP_HAL::I2CDeviceManager * i2c_mgr
Vector3< T > mul_transpose(const Vector3< T > &v) const
uint8_t get_count(void) const
#define HAL_COMPASS_QMC5883L_I2C_ADDR
static float get_declination(float latitude_deg, float longitude_deg)
#define HAL_COMPASS_LIS3MDL_NAME
void set_declination(float radians, bool save_to_eeprom=true)
static constexpr const char * name
float constrain_float(const float amt, const float low, const float high)
#define COMPASS_MAX_INSTANCES
void motor_compensation_type(const uint8_t comp_type)
Matrix3f * _custom_rotation
virtual void accumulate(void)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
static constexpr float radians(float deg)
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
const Vector3f & get_field(void) const
#define ADD_BACKEND(driver_type, backend, name, external)
static Compass * _singleton
#define HAL_COMPASS_HMC5843_I2C_EXT_BUS
static const struct AP_Param::GroupInfo var_info[]
virtual void read(void)=0
static constexpr const char * name
static constexpr const char * name
static AP_Compass_Backend * probe_mpu6000(Compass &compass, enum Rotation rotation=ROTATION_NONE)
void panic(const char *errormsg,...) FMT_PRINTF(1
#define AP_COMPASS_MOT_COMP_CURRENT
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
#define COMPASS_MAX_BACKEND
bool use_for_yaw(void) const
return true if the compass should be used for yaw calculations
struct Compass::mag_state _state[COMPASS_MAX_INSTANCES]
void set_initial_location(int32_t latitude, int32_t longitude)
AP_HAL::Scheduler * scheduler
enum Rotation _board_orientation
AP_Vector3f motor_compensation
#define BOARD_I2C_BUS_EXT
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
static AP_Compass_Backend * probe_ICM20948(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev_icm, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void save_motor_compensation()
#define HAL_COMPASS_HMC5843_NAME