mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: add and use AP_COMPASS_LSM303D_ENABLED
This commit is contained in:
parent
1e003871b0
commit
cbd1264f90
|
@ -1353,11 +1353,15 @@ void Compass::_detect_backends(void)
|
|||
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));
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE));
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));
|
||||
#endif
|
||||
// we run the AK8963 only on the 2nd MPU9250, which leaves the
|
||||
// first MPU9250 to run without disturbance at high rate
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
|
||||
|
@ -1401,7 +1405,9 @@ void Compass::_detect_backends(void)
|
|||
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));
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270));
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
|
@ -415,7 +415,9 @@ private:
|
|||
// enum of drivers for COMPASS_TYPEMASK
|
||||
enum DriverType {
|
||||
DRIVER_HMC5843 =0,
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
DRIVER_LSM303D =1,
|
||||
#endif
|
||||
DRIVER_AK8963 =2,
|
||||
DRIVER_BMM150 =3,
|
||||
DRIVER_LSM9DS1 =4,
|
||||
|
|
|
@ -12,13 +12,16 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Compass_LSM303D.h"
|
||||
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "AP_Compass_LSM303D.h"
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
@ -428,3 +431,5 @@ bool AP_Compass_LSM303D::_mag_set_samplerate(uint16_t frequency)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // AP_COMPASS_LSM303D_ENABLED
|
||||
|
|
|
@ -1,5 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Compass_config.h"
|
||||
|
||||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/Device.h>
|
||||
|
@ -53,3 +57,5 @@ private:
|
|||
uint8_t _mag_samplerate;
|
||||
uint8_t _reg7_expected;
|
||||
};
|
||||
|
||||
#endif // AP_COMPASS_LSM303D_ENABLED
|
||||
|
|
|
@ -37,3 +37,7 @@
|
|||
#ifndef AP_COMPASS_IST8308_ENABLED
|
||||
#define AP_COMPASS_IST8308_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_LSM303D_ENABLED
|
||||
#define AP_COMPASS_LSM303D_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue