Exemple #1
0
/*
  detect available backends for this board
 */
void Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect(*this));
        return;
    }

#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
    _add_backend(AP_Compass_LSM303D::detect_spi(*this));
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_BEBOP
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
    _add_backend(AP_Compass_AK8963::detect_mpu9250(*this, hal.spi->device(AP_HAL::SPIDevice_MPU9250)));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    _add_backend(AP_Compass_HIL::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
    _add_backend(AP_Compass_HMC5843::detect_mpu6000(*this));
#elif  HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
    _add_backend(AP_Compass_AK8963::detect_i2c(*this, hal.i2c1,
                                               HAL_COMPASS_AK8963_I2C_ADDR));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    _add_backend(AP_Compass_PX4::detect(*this));
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.console->println_P(PSTR("No Compass backends available"));
    }
}
/*
  detect available backends for this board
 */
void 
AP_InertialSensor::_detect_backends(void)
{
#if HAL_INS_DEFAULT == HAL_INS_HIL
    _add_backend(AP_InertialSensor_HIL::detect);
#elif HAL_INS_DEFAULT == HAL_INS_MPU6000
    _add_backend(AP_InertialSensor_MPU6000::detect);
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
    _add_backend(AP_InertialSensor_PX4::detect);
#elif HAL_INS_DEFAULT == HAL_INS_OILPAN
    _add_backend(AP_InertialSensor_Oilpan::detect);
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250
    _add_backend(AP_InertialSensor_MPU9250::detect);
#elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE
    _add_backend(AP_InertialSensor_Flymaple::detect);
#else
    #error Unrecognised HAL_INS_TYPE setting
#endif

#if 0 // disabled due to broken hardware on some PXF capes
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
    // the PXF also has a MPU6000
    _add_backend(AP_InertialSensor_MPU6000::detect);
#endif
#endif

    if (_backend_count == 0 ||
        _gyro_count == 0 ||
        _accel_count == 0) {
        hal.scheduler->panic(PSTR("No INS backends available"));
    }

    // set the product ID to the ID of the first backend
    _product_id.set(_backends[0]->product_id());
}
Exemple #3
0
/*
  detect available backends for this board
 */
void 
Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect);
        return;
    }

#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
    _add_backend(AP_Compass_HMC5843::detect);
    _add_backend(AP_Compass_AK8963_MPU9250::detect);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    _add_backend(AP_Compass_HIL::detect);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    _add_backend(AP_Compass_HMC5843::detect);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    _add_backend(AP_Compass_PX4::detect);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
    _add_backend(AP_Compass_AK8963_MPU9250::detect);
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.scheduler->panic(PSTR("No Compass backends available"));
    }
}
Exemple #4
0
/*
  detect if an instance of a rangefinder is connected. 
 */
void RangeFinder::detect_instance(uint8_t instance)
{
    uint8_t type = _type[instance];
    switch (type) {
    case RangeFinder_TYPE_PLI2C:
        if (!_add_backend(AP_RangeFinder_PulsedLightLRF::detect(0, *this, instance, state[instance]))) {
            _add_backend(AP_RangeFinder_PulsedLightLRF::detect(1, *this, instance, state[instance]));
        }
        break;
    case RangeFinder_TYPE_MBI2C:
        _add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(*this, instance, state[instance]));
        break;
    case RangeFinder_TYPE_LWI2C:
        if (_address[instance]) {
            _add_backend(AP_RangeFinder_LightWareI2C::detect(*this, instance, state[instance],
                hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, _address[instance])));
        }
        break;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4  || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
    case RangeFinder_TYPE_PX4:
        if (AP_RangeFinder_PX4::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_PX4(*this, instance, state[instance]);
        }
        break;
    case RangeFinder_TYPE_PX4_PWM:
        if (AP_RangeFinder_PX4_PWM::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_PX4_PWM(*this, instance, state[instance]);
        }
        break;
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
    case RangeFinder_TYPE_BBB_PRU:
        if (AP_RangeFinder_BBB_PRU::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_BBB_PRU(*this, instance, state[instance]);
        }
        break;
#endif
    case RangeFinder_TYPE_LWSER:
        if (AP_RangeFinder_LightWareSerial::detect(*this, instance, serial_manager)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_LightWareSerial(*this, instance, state[instance], serial_manager);
        }
        break;
    case RangeFinder_TYPE_LEDDARONE:
        if (AP_RangeFinder_LeddarOne::detect(*this, instance, serial_manager)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_LeddarOne(*this, instance, state[instance], serial_manager);
        }
        break;
    case RangeFinder_TYPE_ULANDING:
        if (AP_RangeFinder_uLanding::detect(*this, instance, serial_manager)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_uLanding(*this, instance, state[instance], serial_manager);
        }
        break;
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
     CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
    case RangeFinder_TYPE_BEBOP:
        if (AP_RangeFinder_Bebop::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_Bebop(*this, instance, state[instance]);
        }
        break;
#endif
    case RangeFinder_TYPE_MAVLink:
        if (AP_RangeFinder_MAVLink::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_MAVLink(*this, instance, state[instance]);
        }
        break;
    case RangeFinder_TYPE_MBSER:
        if (AP_RangeFinder_MaxsonarSerialLV::detect(*this, instance, serial_manager)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(*this, instance, state[instance], serial_manager);
        }
        break;
    case RangeFinder_TYPE_ANALOG:
        // note that analog will always come back as present if the pin is valid
        if (AP_RangeFinder_analog::detect(*this, instance)) {
            state[instance].instance = instance;
            drivers[instance] = new AP_RangeFinder_analog(*this, instance, state[instance]);
        }
        break;
    default:
        break;
    }
}
Exemple #5
0
/*
  detect available backends for this board
 */
void Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect(*this));
        return;
    }

#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
    _add_backend(AP_Compass_LSM303D::detect_spi(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
    // detect_mpu9250() failed will cause panic if no actual mpu9250 backend,
    // in BH, only one compass should be detected
    AP_Compass_Backend *backend = AP_Compass_HMC5843::detect_i2c(*this, hal.i2c);
    if (backend) {
        _add_backend(backend);
    } else {
        _add_backend(AP_Compass_AK8963::detect_mpu9250(*this, 0));
    }
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
      CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE && \
      CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_BEBOP && \
      CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_QFLIGHT && \
      CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_MINLURE
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
    _add_backend(AP_Compass_AK8963::detect_mpu9250(*this, 0));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    _add_backend(AP_Compass_HIL::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    _add_backend(AP_Compass_HMC5843::detect_i2c(*this, hal.i2c));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
    _add_backend(AP_Compass_HMC5843::detect_mpu6000(*this));
#elif  HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
    _add_backend(AP_Compass_AK8963::detect_i2c(*this, hal.i2c1,
                                               HAL_COMPASS_AK8963_I2C_ADDR));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
    _add_backend(AP_Compass_AK8963::detect_mpu9250_i2c(*this, HAL_COMPASS_AK8963_I2C_POINTER,
                                                       HAL_COMPASS_AK8963_I2C_ADDR));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    _add_backend(AP_Compass_PX4::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
    _add_backend(AP_Compass_AK8963::detect_mpu9250(*this, 0));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QFLIGHT
    _add_backend(AP_Compass_QFLIGHT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
    _add_backend(AP_Compass_QURT::detect(*this));
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.console->println("No Compass backends available");
    }
}
/*
  detect if an instance of a rangefinder is connected. 
 */
void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
{
    enum RangeFinder_Type _type = (enum RangeFinder_Type)state[instance].type.get();
    switch (_type) {
    case RangeFinder_TYPE_PLI2C:
    case RangeFinder_TYPE_PLI2CV3:
        if (!_add_backend(AP_RangeFinder_PulsedLightLRF::detect(1, state[instance], _type))) {
            _add_backend(AP_RangeFinder_PulsedLightLRF::detect(0, state[instance], _type));
        }
        break;
    case RangeFinder_TYPE_MBI2C:
        if (!_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance],
                                                hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) {
            _add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance],
                                               hal.i2c_mgr->get_device(0, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)));
        }
        break;
    case RangeFinder_TYPE_LWI2C:
        if (state[instance].address) {
#ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
            _add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance],
                hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, state[instance].address)));
#else
            if (!_add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance],
                                                                  hal.i2c_mgr->get_device(1, state[instance].address)))) {
                _add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance],
                                                                 hal.i2c_mgr->get_device(0, state[instance].address)));
            }
#endif
        }
        break;
    case RangeFinder_TYPE_TRI2C:
        if (state[instance].address) {
            if (!_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance],
                                                                   hal.i2c_mgr->get_device(1, state[instance].address)))) {
                _add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance],
                                                                  hal.i2c_mgr->get_device(0, state[instance].address)));
            }
        }
        break;
    case RangeFinder_TYPE_VL53L0X:
        if (!_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance],
                                                         hal.i2c_mgr->get_device(1, 0x29)))) {
            _add_backend(AP_RangeFinder_VL53L0X::detect(state[instance],
                                                        hal.i2c_mgr->get_device(0, 0x29)));
        }
        break;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
    case RangeFinder_TYPE_PX4_PWM:
        if (AP_RangeFinder_PX4_PWM::detect()) {
            drivers[instance] = new AP_RangeFinder_PX4_PWM(state[instance], _powersave_range, estimated_terrain_height);
        }
        break;
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
    case RangeFinder_TYPE_BBB_PRU:
        if (AP_RangeFinder_BBB_PRU::detect()) {
            drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance]);
        }
        break;
#endif
    case RangeFinder_TYPE_LWSER:
        if (AP_RangeFinder_LightWareSerial::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], serial_manager, serial_instance++);
        }
        break;
    case RangeFinder_TYPE_LEDDARONE:
        if (AP_RangeFinder_LeddarOne::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], serial_manager, serial_instance++);
        }
        break;
    case RangeFinder_TYPE_ULANDING:
        if (AP_RangeFinder_uLanding::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_uLanding(state[instance], serial_manager, serial_instance++);
        }
        break;
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
     CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
    case RangeFinder_TYPE_BEBOP:
        if (AP_RangeFinder_Bebop::detect()) {
            drivers[instance] = new AP_RangeFinder_Bebop(state[instance]);
        }
        break;
#endif
    case RangeFinder_TYPE_MAVLink:
        if (AP_RangeFinder_MAVLink::detect()) {
            drivers[instance] = new AP_RangeFinder_MAVLink(state[instance]);
        }
        break;
    case RangeFinder_TYPE_MBSER:
        if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], serial_manager, serial_instance++);
        }
        break;
    case RangeFinder_TYPE_ANALOG:
        // note that analog will always come back as present if the pin is valid
        if (AP_RangeFinder_analog::detect(state[instance])) {
            drivers[instance] = new AP_RangeFinder_analog(state[instance]);
        }
        break;
    case RangeFinder_TYPE_NMEA:
        if (AP_RangeFinder_NMEA::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_NMEA(state[instance], serial_manager, serial_instance++);
        }
        break;
    case RangeFinder_TYPE_WASP:
        if (AP_RangeFinder_Wasp::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_Wasp(state[instance], serial_manager, serial_instance++);
        }
        break;
    case RangeFinder_TYPE_BenewakeTF02:
        if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_Benewake(state[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
        }
        break;
    case RangeFinder_TYPE_BenewakeTFmini:
        if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
            drivers[instance] = new AP_RangeFinder_Benewake(state[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
        }
        break;
    default:
        break;
    }

    // if the backend has some local parameters then make those available in the tree
    if (drivers[instance] && state[instance].var_info) {
        backend_var_info[instance] = state[instance].var_info;
        AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
    }
}
/*
  detect available backends for this board
 */
void
AP_InertialSensor::detect_backends(void)
{
    if (_backends_detected)
        return;

    _backends_detected = true;

    if (_hil_mode) {
        _add_backend(AP_InertialSensor_HIL::detect(*this));
        return;
    }
#if HAL_INS_DEFAULT == HAL_INS_HIL
    _add_backend(AP_InertialSensor_HIL::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
#elif HAL_INS_DEFAULT == HAL_INS_BH
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
	_add_backend(AP_InertialSensor_PX4::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE
    _add_backend(AP_InertialSensor_Flymaple::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0
    _add_backend(AP_InertialSensor_LSM9DS0::probe(*this,
                 hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
                 hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_L3G4200D
    _add_backend(AP_InertialSensor_L3G4200D::probe(*this, hal.i2c_mgr->get_device(HAL_INS_L3G4200D_I2C_BUS, HAL_INS_L3G4200D_I2C_ADDR));
#elif HAL_INS_DEFAULT == HAL_INS_RASPILOT
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME)));
    _add_backend(AP_InertialSensor_LSM9DS0::probe(*this,
                 hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
                 hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250_I2C
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU9250_I2C_BUS, HAL_INS_MPU9250_I2C_ADDR));
#elif HAL_INS_DEFAULT == HAL_INS_QFLIGHT
    _add_backend(AP_InertialSensor_QFLIGHT::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_QURT
    _add_backend(AP_InertialSensor_QURT::detect(*this));
#else
    #error Unrecognised HAL_INS_TYPE setting
#endif

    if (_backend_count == 0) {
        AP_HAL::panic("No INS backends available");
    }

    // set the product ID to the ID of the first backend
    _product_id.set(_backends[0]->product_id());
}
/*
  detect available backends for this board
 */
void
AP_InertialSensor::detect_backends(void)
{
    if (_backends_detected)
        return;

    _backends_detected = true;

    if (_hil_mode) {
        _add_backend(AP_InertialSensor_HIL::detect(*this));
        return;
    }
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
    _add_backend(AP_InertialSensor_SITL::detect(*this));    
#elif HAL_INS_DEFAULT == HAL_INS_HIL
    _add_backend(AP_InertialSensor_HIL::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI
    _add_backend(AP_InertialSensor_MPU6000::detect_spi(*this));
#elif HAL_INS_DEFAULT == HAL_INS_BH
    _add_backend(AP_InertialSensor_MPU6000::detect_i2c(*this, hal.i2c, HAL_INS_MPU60XX_I2C_ADDR));
    _add_backend(AP_InertialSensor_MPU9250::detect(*this, hal.spi->device(AP_HAL::SPIDevice_MPU9250)));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C && HAL_INS_MPU60XX_I2C_BUS == 2
    _add_backend(AP_InertialSensor_MPU6000::detect_i2c(*this, hal.i2c2, HAL_INS_MPU60XX_I2C_ADDR));
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
    _add_backend(AP_InertialSensor_PX4::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250
    _add_backend(AP_InertialSensor_MPU9250::detect(*this, hal.spi->device(AP_HAL::SPIDevice_MPU9250)));
#elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE
    _add_backend(AP_InertialSensor_Flymaple::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0
    _add_backend(AP_InertialSensor_LSM9DS0::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_L3G4200D
    _add_backend(AP_InertialSensor_L3G4200D::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_RASPILOT
    //_add_backend(AP_InertialSensor_L3GD20::detect);
    //_add_backend(AP_InertialSensor_LSM303D::detect);
    _add_backend(AP_InertialSensor_MPU6000::detect_spi(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250_I2C
    _add_backend(AP_InertialSensor_MPU9250::detect_i2c(*this,
                                                       HAL_INS_MPU9250_I2C_POINTER,
                                                       HAL_INS_MPU9250_I2C_ADDR));
#elif HAL_INS_DEFAULT == HAL_INS_QFLIGHT
    _add_backend(AP_InertialSensor_QFLIGHT::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_QURT
    _add_backend(AP_InertialSensor_QURT::detect(*this));
#else
    #error Unrecognised HAL_INS_TYPE setting
#endif

    if (_backend_count == 0) {
        AP_HAL::panic("No INS backends available");
    }

    // set the product ID to the ID of the first backend
    _product_id.set(_backends[0]->product_id());
}
Exemple #9
0
/*
  detect available backends for this board
 */
void Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect(*this), nullptr, false);
        return;
    }

#if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    _add_backend(AP_Compass_HIL::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    _add_backend(AP_Compass_PX4::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
    _add_backend(AP_Compass_QURT::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RASPILOT
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
    _add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device("lsm9ds0_am")),
                 AP_Compass_LSM303D::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
    // In BH, only one compass should be detected
    bool ret = _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                            AP_Compass_HMC5843::name, false);
    if (!ret) {
        _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                     AP_Compass_AK8963::name, false);
    }
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QFLIGHT
    _add_backend(AP_Compass_QFLIGHT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 1),
                 AP_Compass_AK8963::name, true);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
    _add_backend(AP_Compass_HMC5843::probe_mpu6000(*this),
                 AP_Compass_HMC5843::name, false);
    _add_backend(AP_Compass_HMC5843::probe(*this,
                     Linux::I2CDeviceManager::from(hal.i2c_mgr)->get_device(
                         { /* UEFI with lpss set to ACPI */
                           "platform/80860F41:05",
                           /* UEFI with lpss set to PCI */
                           "pci0000:00/0000:00:18.6" },
                         HAL_COMPASS_HMC5843_I2C_ADDR),
                     true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    _add_backend(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")),
                 AP_Compass_LSM9DS1::name, false);
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                 AP_Compass_HMC5843::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
    _add_backend(AP_Compass_HMC5843::probe_mpu6000(*this),
                 AP_Compass_HMC5843::name, false);
#elif  HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
    _add_backend(AP_Compass_AK8963::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
                 AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
                 AP_Compass_AK8963::name, false);
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                 AP_Compass_HMC5843::name, false);
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    _add_backend(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")),
                 AP_Compass_LSM9DS1::name, false);
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.console->println("No Compass backends available");
    }
}
Exemple #10
0
/*
  detect available backends for this board
 */
void Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect(*this));
        return;
    }

#if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    _add_backend(AP_Compass_HIL::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    _add_backend(AP_Compass_PX4::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
    _add_backend(AP_Compass_QURT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RASPILOT
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true));
    _add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device("lsm9ds0_am")));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
    // detect_mpu9250() failed will cause panic if no actual mpu9250 backend,
    // in BH, only one compass should be detected
    AP_Compass_Backend *backend = AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR));
    if (backend) {
        _add_backend(backend);
    } else {
        _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0));
    }
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QFLIGHT
    _add_backend(AP_Compass_QFLIGHT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
    AP_Compass_Backend *backend = AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("HMC5843: External compass detected\n");
    } else {
        hal.console->printf("HMC5843: External compass not detected\n");
    }

    backend = AP_Compass_AK8963::probe_mpu9250(*this, 0);
    if (backend) {
        _add_backend(backend);
        hal.console->printf("AK8953: Onboard compass detected\n");
    } else {
        hal.console->printf("AK8953: Onboard compass not detected\n");
    }

    backend = AP_Compass_AK8963::probe_mpu9250(*this, 1);
    if (backend) {
        _add_backend(backend);
        hal.console->printf("AK8953: External compass detected\n");
    } else {
        hal.console->printf("AK8953: External compass not detected\n");
    }
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
    _add_backend(AP_Compass_HMC5843::probe_mpu6000(*this));
    _add_backend(AP_Compass_HMC5843::probe(*this,
        Linux::I2CDeviceManager::from(hal.i2c_mgr)->get_device(
            { /* UEFI with lpss set to ACPI */
              "platform/80860F41:05",
              /* UEFI with lpss set to PCI */
              "pci0000:00/0000:00:18.6" },
            HAL_COMPASS_HMC5843_I2C_ADDR),
        true));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
    AP_Compass_Backend *backend = AP_Compass_AK8963::probe_mpu9250(*this, 0);
    if (backend) {
        _add_backend(backend);
        hal.console->printf("AK8953: Compass detected\n");
    } else {
        hal.console->printf("AK8953: Compass not detected\n");
    }

    backend = AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m"));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("LSM9DS1: Compass detected\n");
    } else {
        hal.console->printf("LSM9DS1: Compass not detected\n");
    }

    backend = AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("HMC5843: External compass detected\n");
    } else {
        hal.console->printf("HMC5843: External compass not detected\n");
    }
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
    AP_Compass_Backend *backend = AP_Compass_AK8963::probe_mpu9250(*this, 0);
    if (backend) {
        _add_backend(backend);
        hal.console->printf("AK8953: Compass detected\n");
    } else {
        hal.console->printf("AK8953: Compass not detected\n");
    }

    backend = AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("HMC5843: External compass detected\n");
    } else {
        hal.console->printf("HMC5843: External compass not detected\n");
    }
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
    _add_backend(AP_Compass_HMC5843::probe_mpu6000(*this));
#elif  HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
    _add_backend(AP_Compass_AK8963::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)));
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
    _add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)));
    _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0));
    _add_backend(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")));
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.console->println("No Compass backends available");
    }
}
/*
  detect available backends for this board
 */
void Compass::_detect_backends(void)
{
    if (_hil_mode) {
        _add_backend(AP_Compass_HIL::detect(*this), nullptr, false);
        return;
    }

/*
  macro to add a backend with check for too many backends or compass
  instances. We don't try to start more than the maximum allowed
 */
#define ADD_BACKEND(backend, name, external) \
    do { _add_backend(backend, name, external);     \
       if (_backend_count == COMPASS_MAX_BACKEND || \
           _compass_count == COMPASS_MAX_INSTANCES) { \
          return; \
        } \
    } while (0)
    
#if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
    ADD_BACKEND(AP_Compass_HIL::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
    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_PIXRACER: {
        bool both_i2c_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
        // external i2c bus
        ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR),
                                               true, ROTATION_ROLL_180),
                     AP_Compass_HMC5843::name, true);
        // internal i2c bus
        ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR),
                                              both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
                    AP_Compass_HMC5843::name, both_i2c_external);
#if !HAL_MINIMIZE_FEATURES
#if 0
        // lis3mdl - this is disabled for now due to an errata on pixhawk2 GPS unit, pending investigation
        ADD_BACKEND(AP_Compass_LIS3MDL::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_LIS3MDL_I2C_ADDR),
                                               true, ROTATION_YAW_90),
                     AP_Compass_LIS3MDL::name, true);
        ADD_BACKEND(AP_Compass_LIS3MDL::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_LIS3MDL_I2C_ADDR),
                                              both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE),
                     AP_Compass_LIS3MDL::name, both_i2c_external);
#endif

        // AK09916
        ADD_BACKEND(AP_Compass_AK09916::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_AK09916_I2C_ADDR),
                                               true, ROTATION_YAW_270),
                     AP_Compass_AK09916::name, true);
        ADD_BACKEND(AP_Compass_AK09916::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_AK09916_I2C_ADDR),
                                              both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE),
                     AP_Compass_AK09916::name, both_i2c_external);
#endif // HAL_MINIMIZE_FEATURES
        }
        break;

    case AP_BoardConfig::PX4_BOARD_AEROFC:
#ifdef HAL_COMPASS_IST8310_I2C_BUS
        ADD_BACKEND(AP_Compass_IST8310::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
                                              ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
#endif
        break;
    default:
        break;
    }
    switch (AP_BoardConfig::get_board_type()) {
    case AP_BoardConfig::PX4_BOARD_PIXHAWK:
        ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
                                               false, ROTATION_PITCH_180),
                     AP_Compass_HMC5843::name, false);
        ADD_BACKEND(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
                     AP_Compass_LSM303D::name, false);
        break;

    case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
        ADD_BACKEND(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270),
                     AP_Compass_LSM303D::name, false);
        // we run the AK8963 only on the 2nd MPU9250, which leaves the
        // first MPU9250 to run without disturbance at high rate
        ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 1, ROTATION_YAW_270),
                     AP_Compass_AK8963::name, false);
        break;

    case AP_BoardConfig::PX4_BOARD_PIXRACER:
        ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
                                               false, ROTATION_PITCH_180),
                     AP_Compass_HMC5843::name, false);
        ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
                     AP_Compass_AK8963::name, false);
        break;

    case AP_BoardConfig::PX4_BOARD_PHMINI:
        ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180),
                     AP_Compass_AK8963::name, false);
        break;

    case AP_BoardConfig::PX4_BOARD_AUAV21:
        ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
                     AP_Compass_AK8963::name, false);
        break;
        
    case AP_BoardConfig::PX4_BOARD_PH2SLIM:
        ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_YAW_270),
                     AP_Compass_AK8963::name, false);
        break;

    default:
        break;
    }

#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
    ADD_BACKEND(AP_Compass_QURT::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RASPILOT
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
    ADD_BACKEND(AP_Compass_LSM303D::probe(*this, hal.spi->get_device("lsm9ds0_am")),
                 AP_Compass_LSM303D::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                AP_Compass_HMC5843::name, false);
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0), AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QFLIGHT
    ADD_BACKEND(AP_Compass_QFLIGHT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 1),
                 AP_Compass_AK8963::name, true);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
    ADD_BACKEND(AP_Compass_HMC5843::probe_mpu6000(*this),
                 AP_Compass_HMC5843::name, false);
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this,
                     Linux::I2CDeviceManager::from(hal.i2c_mgr)->get_device(
                         { /* UEFI with lpss set to ACPI */
                           "platform/80860F41:05",
                           /* UEFI with lpss set to PCI */
                           "pci0000:00/0000:00:18.6" },
                         HAL_COMPASS_HMC5843_I2C_ADDR),
                     true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
    ADD_BACKEND(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m"), ROTATION_ROLL_180),
                 AP_Compass_LSM9DS1::name, false);
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
                 AP_Compass_HMC5843::name, true);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                 AP_Compass_HMC5843::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
    ADD_BACKEND(AP_Compass_HMC5843::probe_mpu6000(*this),
                 AP_Compass_HMC5843::name, false);
#elif  HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
    ADD_BACKEND(AP_Compass_AK8963::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
                 AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
                 AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AERO
    ADD_BACKEND(AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
                 AP_Compass_BMM150::name, false);
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
    ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
                 AP_Compass_HMC5843::name, false);
    ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0),
                 AP_Compass_AK8963::name, false);
    ADD_BACKEND(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")),
                 AP_Compass_LSM9DS1::name, false);
#else
    #error Unrecognised HAL_COMPASS_TYPE setting
#endif

#if HAL_WITH_UAVCAN
    if ((AP_BoardConfig::get_can_enable() != 0) && (hal.can_mgr != nullptr))
    {
        if((_backend_count < COMPASS_MAX_BACKEND) && (_compass_count < COMPASS_MAX_INSTANCES))
        {
            printf("Creating AP_Compass_UAVCAN\n\r");
            _backends[_backend_count] = new AP_Compass_UAVCAN(*this);
            _backend_count++;
        }
    }
#endif

    if (_backend_count == 0 ||
        _compass_count == 0) {
        hal.console->printf("No Compass backends available\n");
    }
}
Exemple #12
0
/*
  initialise the barometer object, loading backend drivers
 */
void AP_Baro::init(void)
{
    // ensure that there isn't a previous ground temperature saved
    if (!is_zero(_user_ground_temperature)) {
        _user_ground_temperature.set_and_save(0.0f);
        _user_ground_temperature.notify();
    }

    if (_hil_mode) {
        drivers[0] = new AP_Baro_HIL(*this);
        _num_drivers = 1;
        return;
    }

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
    ADD_BACKEND(new AP_Baro_SITL(*this));
    return;
#endif
    
#if HAL_WITH_UAVCAN
    bool added;
    do {
        added = _add_backend(AP_Baro_UAVCAN::probe(*this));
        if (_num_drivers == BARO_MAX_DRIVERS || _num_sensors == BARO_MAX_INSTANCES) {
            return;
        }
    } while (added);
#endif

#if HAL_BARO_DEFAULT == HAL_BARO_PX4 || HAL_BARO_DEFAULT == HAL_BARO_VRBRAIN
    switch (AP_BoardConfig::get_board_type()) {
    case AP_BoardConfig::PX4_BOARD_PX4V1:
#ifdef HAL_BARO_MS5611_I2C_BUS
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));
#endif
        break;

    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_PIXHAWK_PRO:
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
        break;

    case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
        break;

    case AP_BoardConfig::PX4_BOARD_PIXRACER:
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_INT_NAME))));
        break;

    case AP_BoardConfig::PX4_BOARD_AEROFC:
#ifdef HAL_BARO_MS5607_I2C_BUS
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
                                          AP_Baro_MS56XX::BARO_MS5607));
#endif
        break;

    default:
        break;
    }
#elif HAL_BARO_DEFAULT == HAL_BARO_HIL
    drivers[0] = new AP_Baro_HIL(*this);
    _num_drivers = 1;
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP085
    drivers[0] = new AP_Baro_BMP085(*this,
        std::move(hal.i2c_mgr->get_device(HAL_BARO_BMP085_BUS, HAL_BARO_BMP085_I2C_ADDR)));
    _num_drivers = 1;
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_I2C
    ADD_BACKEND(AP_Baro_BMP280::probe(*this,
                                      std::move(hal.i2c_mgr->get_device(HAL_BARO_BMP280_BUS, HAL_BARO_BMP280_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_SPI
    ADD_BACKEND(AP_Baro_BMP280::probe(*this,
                                      std::move(hal.spi->get_device(HAL_BARO_BMP280_NAME))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_I2C
    ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                      std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI
    ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                      std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5607_I2C
    ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                      std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
                                      AP_Baro_MS56XX::BARO_MS5607));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5637_I2C
    ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                      std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)),
                                      AP_Baro_MS56XX::BARO_MS5637));
#elif HAL_BARO_DEFAULT == HAL_BARO_QFLIGHT
    drivers[0] = new AP_Baro_QFLIGHT(*this);
    _num_drivers = 1;
#elif HAL_BARO_DEFAULT == HAL_BARO_QURT
    drivers[0] = new AP_Baro_QURT(*this);
    _num_drivers = 1;
#elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H
	ADD_BACKEND(AP_Baro_LPS25H::probe(*this,
                                      std::move(hal.i2c_mgr->get_device(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR))));
#endif

    // can optionally have baro on I2C too
    if (_ext_bus >= 0) {
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.i2c_mgr->get_device(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837));

        ADD_BACKEND(AP_Baro_KellerLD::probe(*this,
                                          std::move(hal.i2c_mgr->get_device(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR))));
#else
        ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
                                          std::move(hal.i2c_mgr->get_device(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));
#endif
    }

    if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
        AP_BoardConfig::sensor_config_error("Baro: unable to initialise driver");
    }
}
Exemple #13
0
/*
  detect available backends for this board
 */
void
AP_InertialSensor::detect_backends(void)
{
    if (_backends_detected)
        return;

    _backends_detected = true;

    if (_hil_mode) {
        _add_backend(AP_InertialSensor_HIL::detect(*this));
        return;
    }
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
    _add_backend(AP_InertialSensor_SITL::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_HIL
    _add_backend(AP_InertialSensor_HIL::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
#elif HAL_INS_DEFAULT == HAL_INS_BH
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN
    _add_backend(AP_InertialSensor_PX4::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0
    _add_backend(AP_InertialSensor_LSM9DS0::probe(*this,
                 hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
                 hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_L3G4200D
    _add_backend(AP_InertialSensor_L3G4200D::probe(*this, hal.i2c_mgr->get_device(HAL_INS_L3G4200D_I2C_BUS, HAL_INS_L3G4200D_I2C_ADDR)));
#elif HAL_INS_DEFAULT == HAL_INS_RASPILOT
    _add_backend(AP_InertialSensor_MPU6000::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME)));
    _add_backend(AP_InertialSensor_LSM9DS0::probe(*this,
                 hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
                 hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)));
#elif HAL_INS_DEFAULT == HAL_INS_MPU9250_I2C
    _add_backend(AP_InertialSensor_MPU9250::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU9250_I2C_BUS, HAL_INS_MPU9250_I2C_ADDR)));
#elif HAL_INS_DEFAULT == HAL_INS_QFLIGHT
    _add_backend(AP_InertialSensor_QFLIGHT::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_QURT
    _add_backend(AP_InertialSensor_QURT::detect(*this));
#elif HAL_INS_DEFAULT == HAL_INS_BBBMINI
    AP_InertialSensor_Backend *backend = AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("MPU9250: Onboard IMU detected\n");
    } else {
        hal.console->printf("MPU9250: Onboard IMU not detected\n");
    }

    backend = AP_InertialSensor_MPU9250::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME_EXT));
    if (backend) {
        _add_backend(backend);
        hal.console->printf("MPU9250: External IMU detected\n");
    } else {
        hal.console->printf("MPU9250: External IMU not detected\n");
    }
#else
    #error Unrecognised HAL_INS_TYPE setting
#endif

    if (_backend_count == 0) {
        AP_HAL::panic("No INS backends available");
    }

    // set the product ID to the ID of the first backend
    _product_id.set(_backends[0]->product_id());
}