123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299 |
- #include <AP_HAL/AP_HAL.h>
- #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
- #include <AP_HAL_Linux/I2CDevice.h>
- #endif
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <AP_BoardConfig/AP_BoardConfig.h>
- #include <AP_Logger/AP_Logger.h>
- #include "AP_Compass_SITL.h"
- #include "AP_Compass_AK8963.h"
- #include "AP_Compass_Backend.h"
- #include "AP_Compass_BMM150.h"
- #include "AP_Compass_HIL.h"
- #include "AP_Compass_HMC5843.h"
- #include "AP_Compass_IST8308.h"
- #include "AP_Compass_IST8310.h"
- #include "AP_Compass_LSM303D.h"
- #include "AP_Compass_LSM9DS1.h"
- #include "AP_Compass_LIS3MDL.h"
- #include "AP_Compass_AK09916.h"
- #include "AP_Compass_QMC5883L.h"
- #if HAL_WITH_UAVCAN
- #include "AP_Compass_UAVCAN.h"
- #endif
- #include "AP_Compass_MMC3416.h"
- #include "AP_Compass_MAG3110.h"
- #include "AP_Compass_RM3100.h"
- #include "AP_Compass.h"
- #include "Compass_learn.h"
- extern AP_HAL::HAL& hal;
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
- #define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
- #else
- #define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL
- #endif
- #ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
- #define AP_COMPASS_OFFSETS_MAX_DEFAULT 1800
- #endif
- #ifndef HAL_COMPASS_FILTER_DEFAULT
- #define HAL_COMPASS_FILTER_DEFAULT 0
- #endif
- #ifndef HAL_COMPASS_AUTO_ROT_DEFAULT
- #define HAL_COMPASS_AUTO_ROT_DEFAULT 2
- #endif
- const AP_Param::GroupInfo Compass::var_info[] = {
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("OFS", 1, Compass, _state[0].offset, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
-
-
-
-
-
- AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("USE", 4, Compass, _state[0].use_for_yaw, 1),
-
-
-
-
-
- AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),
-
-
-
-
-
- AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("MOT", 7, Compass, _state[0].motor_compensation, 0),
-
-
-
-
-
- AP_GROUPINFO("ORIENT", 8, Compass, _state[0].orientation, ROTATION_NONE),
-
-
-
-
-
- AP_GROUPINFO("EXTERNAL", 9, Compass, _state[0].external, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("OFS2", 10, Compass, _state[1].offset, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("MOT2", 11, Compass, _state[1].motor_compensation, 0),
-
-
-
-
-
- AP_GROUPINFO("PRIMARY", 12, Compass, _primary, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("OFS3", 13, Compass, _state[2].offset, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("MOT3", 14, Compass, _state[2].motor_compensation, 0),
-
-
-
-
-
- AP_GROUPINFO("DEV_ID", 15, Compass, _state[0].dev_id, 0),
-
-
-
-
-
- AP_GROUPINFO("DEV_ID2", 16, Compass, _state[1].dev_id, 0),
-
-
-
-
-
- AP_GROUPINFO("DEV_ID3", 17, Compass, _state[2].dev_id, 0),
-
-
-
-
-
- AP_GROUPINFO("USE2", 18, Compass, _state[1].use_for_yaw, 1),
-
-
-
-
-
- AP_GROUPINFO("ORIENT2", 19, Compass, _state[1].orientation, ROTATION_NONE),
-
-
-
-
-
- AP_GROUPINFO("EXTERN2",20, Compass, _state[1].external, 0),
-
-
-
-
-
- AP_GROUPINFO("USE3", 21, Compass, _state[2].use_for_yaw, 1),
-
-
-
-
-
- AP_GROUPINFO("ORIENT3", 22, Compass, _state[2].orientation, ROTATION_NONE),
-
-
-
-
-
- AP_GROUPINFO("EXTERN3",23, Compass, _state[2].external, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("DIA", 24, Compass, _state[0].diagonals, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ODI", 25, Compass, _state[0].offdiagonals, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("DIA2", 26, Compass, _state[1].diagonals, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ODI2", 27, Compass, _state[1].offdiagonals, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("DIA3", 28, Compass, _state[2].diagonals, 0),
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ODI3", 29, Compass, _state[2].offdiagonals, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT),
- #if COMPASS_MOT_ENABLED
-
-
- AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),
- #endif
-
-
-
-
-
- AP_GROUPINFO("TYPEMASK", 33, Compass, _driver_type_mask, 0),
-
-
-
-
-
-
- AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT),
-
-
-
-
- AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),
-
-
-
-
- AP_GROUPINFO("EXP_DID", 36, Compass, _state[0].expected_dev_id, -1),
-
-
-
-
- AP_GROUPINFO("EXP_DID2", 37, Compass, _state[1].expected_dev_id, -1),
-
-
-
-
- AP_GROUPINFO("EXP_DID3", 38, Compass, _state[2].expected_dev_id, -1),
-
-
-
-
-
- AP_GROUPINFO("ENABLE", 39, Compass, _enabled, 1),
- AP_GROUPEND
- };
- Compass::Compass(void)
- {
- if (_singleton != nullptr) {
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- AP_HAL::panic("Compass must be singleton");
- #endif
- return;
- }
- _singleton = this;
- AP_Param::setup_object_defaults(this, var_info);
- }
- void Compass::init()
- {
- if (!AP::compass().enabled()) {
- return;
- }
- if (_compass_count == 0) {
-
- _detect_backends();
- }
- if (_compass_count != 0) {
-
- hal.scheduler->delay(100);
- read();
- }
-
-
-
-
-
- for (uint8_t i=_compass_count; i<COMPASS_MAX_INSTANCES; i++) {
- _state[i].dev_id.set(0);
- }
-
-
- if (!read()) {
- #ifndef HAL_BUILD_AP_PERIPH
- _enabled = false;
- hal.console->printf("Compass initialisation failed\n");
- #endif
- #ifndef HAL_NO_LOGGING
- AP::logger().Write_Error(LogErrorSubsystem::COMPASS, LogErrorCode::FAILED_TO_INITIALISE);
- #endif
- return;
- }
- #ifndef HAL_BUILD_AP_PERIPH
- AP::ahrs().set_compass(this);
- #endif
- }
- uint8_t Compass::register_compass(void)
- {
- if (_compass_count == COMPASS_MAX_INSTANCES) {
- AP_HAL::panic("Too many compass instances");
- }
- return _compass_count++;
- }
- bool Compass::_add_backend(AP_Compass_Backend *backend)
- {
- if (!backend) {
- return false;
- }
- if (_backend_count == COMPASS_MAX_BACKEND) {
- AP_HAL::panic("Too many compass backends");
- }
- _backends[_backend_count++] = backend;
- return true;
- }
- bool Compass::_driver_enabled(enum DriverType driver_type)
- {
- uint32_t mask = (1U<<uint8_t(driver_type));
- return (mask & uint32_t(_driver_type_mask.get())) == 0;
- }
- bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const
- {
- for (uint8_t i=0; i<_compass_count; i++) {
- if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==
- AP_HAL::Device::change_bus_id(uint32_t(_state[i].dev_id.get()), 0)) {
-
- return true;
- }
- }
- return false;
- }
- #define ADD_BACKEND(driver_type, backend) \
- do { if (_driver_enabled(driver_type)) { _add_backend(backend); } \
- if (_backend_count == COMPASS_MAX_BACKEND || \
- _compass_count == COMPASS_MAX_INSTANCES) { \
- return; \
- } \
- } while (0)
- #define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address)
- void Compass::_probe_external_i2c_compasses(void)
- {
- bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
- true, ROTATION_ROLL_180));
- }
-
- if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 &&
- AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {
-
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
- all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));
- }
- }
-
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
- true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL));
- }
-
-
- if (all_external) {
-
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
- all_external,
- all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
- }
- }
-
- #if !HAL_MINIMIZE_FEATURES
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
- GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
- true, ROTATION_PITCH_180_YAW_90));
- }
-
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
- GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
- all_external, ROTATION_PITCH_180_YAW_90));
- }
-
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
- all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
- }
-
-
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
- all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
- }
-
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
- true, ROTATION_YAW_90));
- }
-
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
- true, ROTATION_YAW_90));
- }
-
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
- true, ROTATION_YAW_270));
- }
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
- all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
- }
-
-
- if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&
- AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {
- enum Rotation default_rotation;
- if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) {
- default_rotation = ROTATION_PITCH_180_YAW_90;
- } else {
- default_rotation = ROTATION_PITCH_180;
- }
-
- const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };
- for (uint8_t a=0; a<ARRAY_SIZE(ist8310_addr); a++) {
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
- true, default_rotation));
- }
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
- all_external, default_rotation));
- }
- }
- }
-
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
- true, ROTATION_NONE));
- }
- #endif
- }
- void Compass::_detect_backends(void)
- {
- if (_hil_mode) {
- _add_backend(AP_Compass_HIL::detect());
- return;
- }
- #if AP_FEATURE_BOARD_DETECT
- if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
-
- _driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
- }
- #endif
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL());
- return;
- #endif
- #ifdef HAL_PROBE_EXTERNAL_I2C_COMPASSES
-
- _probe_external_i2c_compasses();
- if (_backend_count == COMPASS_MAX_BACKEND ||
- _compass_count == COMPASS_MAX_INSTANCES) {
- return;
- }
- #endif
- #if defined(HAL_MAG_PROBE_LIST)
-
- HAL_MAG_PROBE_LIST;
- #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
- ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect());
- #elif AP_FEATURE_BOARD_DETECT
- switch (AP_BoardConfig::get_board_type()) {
- case AP_BoardConfig::PX4_BOARD_PX4V1:
- case AP_BoardConfig::PX4_BOARD_PIXHAWK:
- case AP_BoardConfig::PX4_BOARD_PHMINI:
- case AP_BoardConfig::PX4_BOARD_AUAV21:
- case AP_BoardConfig::PX4_BOARD_PH2SLIM:
- case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
- case AP_BoardConfig::PX4_BOARD_MINDPXV2:
- case AP_BoardConfig::PX4_BOARD_FMUV5:
- case AP_BoardConfig::PX4_BOARD_FMUV6:
- case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
- case AP_BoardConfig::PX4_BOARD_AEROFC:
- _probe_external_i2c_compasses();
- if (_backend_count == COMPASS_MAX_BACKEND ||
- _compass_count == COMPASS_MAX_INSTANCES) {
- return;
- }
- break;
- case AP_BoardConfig::PX4_BOARD_PCNC1:
- ADD_BACKEND(DRIVER_BMM150,
- AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), ROTATION_NONE));
- break;
- case AP_BoardConfig::VRX_BOARD_BRAIN54: {
-
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
- true, ROTATION_ROLL_180));
- }
-
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
- false, ROTATION_YAW_270));
- break;
- case AP_BoardConfig::VRX_BOARD_BRAIN51:
- case AP_BoardConfig::VRX_BOARD_BRAIN52:
- case AP_BoardConfig::VRX_BOARD_BRAIN52E:
- case AP_BoardConfig::VRX_BOARD_CORE10:
- case AP_BoardConfig::VRX_BOARD_UBRAIN51:
- case AP_BoardConfig::VRX_BOARD_UBRAIN52: {
-
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
- true, ROTATION_ROLL_180));
- }
- break;
- default:
- break;
- }
- switch (AP_BoardConfig::get_board_type()) {
- case AP_BoardConfig::PX4_BOARD_PIXHAWK:
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
- false, ROTATION_PITCH_180));
- ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE));
- break;
- case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
- ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));
-
-
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
- ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
- break;
- case AP_BoardConfig::PX4_BOARD_FMUV5:
- case AP_BoardConfig::PX4_BOARD_FMUV6:
- FOREACH_I2C_EXTERNAL(i) {
- ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
- true, ROTATION_ROLL_180_YAW_90));
- }
- FOREACH_I2C_INTERNAL(i) {
- ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
- false, ROTATION_ROLL_180_YAW_90));
- }
- break;
-
- case AP_BoardConfig::PX4_BOARD_SP01:
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
- break;
-
- case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
- ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
- false, ROTATION_NONE));
- break;
- case AP_BoardConfig::PX4_BOARD_PHMINI:
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));
- break;
- case AP_BoardConfig::PX4_BOARD_AUAV21:
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
- break;
-
- case AP_BoardConfig::PX4_BOARD_PH2SLIM:
- ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));
- break;
- case AP_BoardConfig::PX4_BOARD_MINDPXV2:
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
- false, ROTATION_YAW_90));
- ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270));
- break;
-
- default:
- break;
- }
- #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE
-
- #else
- #error Unrecognised HAL_COMPASS_TYPE setting
- #endif
- #ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS
- ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
- true, ROTATION_ROLL_180));
- #endif
- #if HAL_WITH_UAVCAN
- for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
- ADD_BACKEND(DRIVER_UAVCAN, AP_Compass_UAVCAN::probe());
- }
- #endif
- if (_backend_count == 0 ||
- _compass_count == 0) {
- hal.console->printf("No Compass backends available\n");
- }
- }
- bool
- Compass::read(void)
- {
- #ifndef HAL_BUILD_AP_PERIPH
- if (!_initial_location_set) {
- try_set_initial_location();
- }
- #endif
- for (uint8_t i=0; i< _backend_count; i++) {
-
- _backends[i]->read();
- }
- uint32_t time = AP_HAL::millis();
- for (uint8_t i=0; i < COMPASS_MAX_INSTANCES; i++) {
- _state[i].healthy = (time - _state[i].last_update_ms < 500);
- }
- #if COMPASS_LEARN_ENABLED
- if (_learn == LEARN_INFLIGHT && !learn_allocated) {
- learn_allocated = true;
- learn = new CompassLearn(*this);
- }
- if (_learn == LEARN_INFLIGHT && learn != nullptr) {
- learn->update();
- }
- bool ret = healthy();
- if (ret && _log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit) && !AP::ahrs().have_ekf_logging()) {
- AP::logger().Write_Compass();
- }
- return ret;
- #else
- return healthy();
- #endif
- }
- uint8_t
- Compass::get_healthy_mask() const
- {
- uint8_t healthy_mask = 0;
- for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
- if(healthy(i)) {
- healthy_mask |= 1 << i;
- }
- }
- return healthy_mask;
- }
- void
- Compass::set_offsets(uint8_t i, const Vector3f &offsets)
- {
-
- if (i < COMPASS_MAX_INSTANCES) {
- _state[i].offset.set(offsets);
- }
- }
- void
- Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
- {
-
- if (i < COMPASS_MAX_INSTANCES) {
- _state[i].offset.set(offsets);
- save_offsets(i);
- }
- }
- void
- Compass::set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
- {
-
- if (i < COMPASS_MAX_INSTANCES) {
- _state[i].diagonals.set_and_save(diagonals);
- }
- }
- void
- Compass::set_and_save_offdiagonals(uint8_t i, const Vector3f &offdiagonals)
- {
-
- if (i < COMPASS_MAX_INSTANCES) {
- _state[i].offdiagonals.set_and_save(offdiagonals);
- }
- }
- void
- Compass::save_offsets(uint8_t i)
- {
- _state[i].offset.save();
- _state[i].dev_id.set_and_save(_state[i].detected_dev_id);
- }
- void
- Compass::save_offsets(void)
- {
- for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
- save_offsets(i);
- }
- }
- void
- Compass::set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
- {
- _state[i].motor_compensation.set(motor_comp_factor);
- }
- void
- Compass::save_motor_compensation()
- {
- _motor_comp_type.save();
- for (uint8_t k=0; k<COMPASS_MAX_INSTANCES; k++) {
- _state[k].motor_compensation.save();
- }
- }
- void Compass::try_set_initial_location()
- {
- if (!_auto_declination) {
- return;
- }
- if (!_enabled) {
- return;
- }
- Location loc;
- if (!AP::ahrs().get_position(loc)) {
- return;
- }
- _initial_location_set = true;
-
-
-
- _declination.set(radians(
- AP_Declination::get_declination(
- (float)loc.lat / 10000000,
- (float)loc.lng / 10000000)));
- }
- bool
- Compass::use_for_yaw(void) const
- {
- uint8_t prim = get_primary();
- return healthy(prim) && use_for_yaw(prim);
- }
- bool
- Compass::use_for_yaw(uint8_t i) const
- {
-
-
-
- return _state[i].use_for_yaw && _learn.get() != LEARN_INFLIGHT;
- }
- void
- Compass::set_declination(float radians, bool save_to_eeprom)
- {
- if (save_to_eeprom) {
- _declination.set_and_save(radians);
- }else{
- _declination.set(radians);
- }
- }
- float
- Compass::get_declination() const
- {
- return _declination.get();
- }
- float
- Compass::calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const
- {
- float cos_pitch_sq = 1.0f-(dcm_matrix.c.x*dcm_matrix.c.x);
-
- const Vector3f &field = get_field(i);
- float headY = field.y * dcm_matrix.c.z - field.z * dcm_matrix.c.y;
-
- float headX = field.x * cos_pitch_sq - dcm_matrix.c.x * (field.y * dcm_matrix.c.y + field.z * dcm_matrix.c.z);
-
-
- float heading = constrain_float(atan2f(-headY,headX), -3.15f, 3.15f);
-
- if( fabsf(_declination) > 0.0f )
- {
- heading = heading + _declination;
- if (heading > M_PI)
- heading -= (2.0f * M_PI);
- else if (heading < -M_PI)
- heading += (2.0f * M_PI);
- }
- return heading;
- }
- bool Compass::configured(uint8_t i)
- {
-
- if (i > get_count()) {
- return false;
- }
-
- if (is_zero(get_offsets(i).length())) {
- return false;
- }
-
- if (_state[i].detected_dev_id == 0) {
- return false;
- }
-
- int32_t dev_id_cache_value = _state[i].dev_id;
-
- _state[i].dev_id.load();
-
- if (_state[i].dev_id != _state[i].detected_dev_id || _state[i].dev_id != dev_id_cache_value) {
-
- _state[i].dev_id = dev_id_cache_value;
-
- return false;
- }
-
- if (_state[i].expected_dev_id != -1 && _state[i].expected_dev_id != _state[i].dev_id) {
- return false;
- }
-
- return true;
- }
- bool Compass::configured(void)
- {
- bool all_configured = true;
- for(uint8_t i=0; i<get_count(); i++) {
- all_configured = all_configured && (!use_for_yaw(i) || configured(i));
- }
- return all_configured;
- }
- void Compass::setHIL(uint8_t instance, float roll, float pitch, float yaw)
- {
- Matrix3f R;
-
- R.from_euler(roll, pitch, yaw);
- if (!is_equal(_hil.last_declination,get_declination())) {
- _setup_earth_field();
- _hil.last_declination = get_declination();
- }
-
-
- _hil.field[instance] = R.mul_transpose(_hil.Bearth);
-
-
- _hil.field[instance].rotate(MAG_BOARD_ORIENTATION);
-
- _hil.field[instance].rotate((enum Rotation)_state[0].orientation.get());
- if (!_state[0].external) {
-
- if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
- _hil.field[instance] = *_custom_rotation * _hil.field[instance];
- } else {
- _hil.field[instance].rotate(_board_orientation);
- }
- }
- _hil.healthy[instance] = true;
- }
- void Compass::setHIL(uint8_t instance, const Vector3f &mag, uint32_t update_usec)
- {
- _hil.field[instance] = mag;
- _hil.healthy[instance] = true;
- _state[instance].last_update_usec = update_usec;
- }
- const Vector3f& Compass::getHIL(uint8_t instance) const
- {
- return _hil.field[instance];
- }
- void Compass::_setup_earth_field(void)
- {
-
- _hil.Bearth(400, 0, 0);
-
-
- Matrix3f R;
- R.from_euler(0, ToRad(66), get_declination());
- _hil.Bearth = R * _hil.Bearth;
- }
- void Compass::motor_compensation_type(const uint8_t comp_type)
- {
- if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {
- _motor_comp_type = (int8_t)comp_type;
- _thr = 0;
- for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
- set_motor_compensation(i, Vector3f(0,0,0));
- }
- }
- }
- bool Compass::consistent() const
- {
- const Vector3f &primary_mag_field = get_field();
- const Vector2f primary_mag_field_xy = Vector2f(primary_mag_field.x,primary_mag_field.y);
- if (primary_mag_field_xy.is_zero()) {
- return false;
- }
- const Vector3f primary_mag_field_norm = primary_mag_field.normalized();
- const Vector2f primary_mag_field_xy_norm = primary_mag_field_xy.normalized();
- for (uint8_t i=0; i<get_count(); i++) {
- if (!use_for_yaw(i)) {
-
- continue;
- }
- Vector3f mag_field = get_field(i);
- Vector2f mag_field_xy = Vector2f(mag_field.x,mag_field.y);
- if (mag_field_xy.is_zero()) {
- return false;
- }
- const float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();
- mag_field.normalize();
- mag_field_xy.normalize();
- const float xyz_ang_diff = acosf(constrain_float(mag_field*primary_mag_field_norm,-1.0f,1.0f));
- const float xy_ang_diff = acosf(constrain_float(mag_field_xy*primary_mag_field_xy_norm,-1.0f,1.0f));
-
- if (xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF) {
- return false;
- }
-
- if (xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF) {
- return false;
- }
-
- if (xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF) {
- return false;
- }
- }
- return true;
- }
- Compass *Compass::_singleton;
- namespace AP {
- Compass &compass()
- {
- return *Compass::get_singleton();
- }
- }
|