mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: make device IDs match PX4 drivers
match in-tree drivers to PX4Firmware drivers
This commit is contained in:
parent
aa4025bdf9
commit
147b253e65
|
@ -511,10 +511,10 @@ void Compass::_detect_backends(void)
|
|||
AP_Compass_LSM303D::name, false);
|
||||
}
|
||||
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3) {
|
||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME)),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME)),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 1),
|
||||
AP_Compass_AK8963::name, false);
|
||||
}
|
||||
|
|
|
@ -12,17 +12,6 @@
|
|||
#include "CompassCalibrator.h"
|
||||
#include "AP_Compass_Backend.h"
|
||||
|
||||
// compass product id
|
||||
#define AP_COMPASS_TYPE_UNKNOWN 0x00
|
||||
#define AP_COMPASS_TYPE_HIL 0x01
|
||||
#define AP_COMPASS_TYPE_HMC5843 0x02
|
||||
#define AP_COMPASS_TYPE_PX4 0x04
|
||||
#define AP_COMPASS_TYPE_VRBRAIN 0x05
|
||||
#define AP_COMPASS_TYPE_AK8963 0x06
|
||||
#define AP_COMPASS_TYPE_LSM303D 0x08
|
||||
#define AP_COMPASS_TYPE_LSM9DS1 0x09
|
||||
#define AP_COMPASS_TYPE_BMM150 0x0A
|
||||
|
||||
// motor compensation types (for use with motor_comp_enabled)
|
||||
#define AP_COMPASS_MOT_COMP_DISABLED 0x00
|
||||
#define AP_COMPASS_MOT_COMP_THROTTLE 0x01
|
||||
|
|
|
@ -149,7 +149,7 @@ bool AP_Compass_AK8963::init()
|
|||
/* register the compass instance in the frontend */
|
||||
_compass_instance = register_compass();
|
||||
|
||||
_bus->set_device_type(AP_COMPASS_TYPE_AK8963);
|
||||
_bus->set_device_type(DEVTYPE_AK8963);
|
||||
set_dev_id(_compass_instance, _bus->get_bus_id());
|
||||
|
||||
bus_sem->give();
|
||||
|
|
|
@ -183,7 +183,7 @@ bool AP_Compass_BMM150::init()
|
|||
/* register the compass instance in the frontend */
|
||||
_compass_instance = register_compass();
|
||||
|
||||
_dev->set_device_type(AP_COMPASS_TYPE_BMM150);
|
||||
_dev->set_device_type(DEVTYPE_BMM150);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
_dev->register_periodic_callback(MEASURE_TIME_USEC,
|
||||
|
|
|
@ -41,6 +41,23 @@ public:
|
|||
// backends
|
||||
virtual void accumulate(void) {};
|
||||
|
||||
/*
|
||||
device driver IDs. These are used to fill in the devtype field
|
||||
of the device ID, which shows up as COMPASS*ID* parameters to
|
||||
users. The values are chosen for compatibility with existing PX4
|
||||
drivers.
|
||||
If a change is made to a driver that would make existing
|
||||
calibration values invalid then this number must be changed.
|
||||
*/
|
||||
enum DevTypes {
|
||||
DEVTYPE_HMC5883 = 0x01,
|
||||
DEVTYPE_LSM303D = 0x02,
|
||||
DEVTYPE_AK8963 = 0x04,
|
||||
DEVTYPE_BMM150 = 0x05,
|
||||
DEVTYPE_LSM9DS1 = 0x06,
|
||||
};
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
/*
|
||||
|
|
|
@ -181,7 +181,7 @@ bool AP_Compass_HMC5843::init()
|
|||
|
||||
_compass_instance = register_compass();
|
||||
|
||||
_bus->set_device_type(AP_COMPASS_TYPE_HMC5843);
|
||||
_bus->set_device_type(DEVTYPE_HMC5883);
|
||||
set_dev_id(_compass_instance, _bus->get_bus_id());
|
||||
|
||||
if (_force_external) {
|
||||
|
|
|
@ -269,7 +269,7 @@ bool AP_Compass_LSM303D::init()
|
|||
/* register the compass instance in the frontend */
|
||||
_compass_instance = register_compass();
|
||||
|
||||
_dev->set_device_type(AP_COMPASS_TYPE_LSM303D);
|
||||
_dev->set_device_type(DEVTYPE_LSM303D);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||
|
|
|
@ -95,7 +95,7 @@ bool AP_Compass_LSM9DS1::init()
|
|||
|
||||
_compass_instance = register_compass();
|
||||
|
||||
_dev->set_device_type(AP_COMPASS_TYPE_LSM9DS1);
|
||||
_dev->set_device_type(DEVTYPE_LSM9DS1);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
_dev->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM9DS1::_update, bool));
|
||||
|
|
Loading…
Reference in New Issue