mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: add and use AP_COMPASS_AK8963_ENABLED
This commit is contained in:
parent
7a7f84adee
commit
22feb3c08a
|
@ -1368,9 +1368,11 @@ void Compass::_detect_backends(void)
|
|||
#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
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
// 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));
|
||||
#endif
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
|
||||
break;
|
||||
|
||||
|
@ -1387,25 +1389,35 @@ void Compass::_detect_backends(void)
|
|||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_SP01:
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
|
||||
#endif
|
||||
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:
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_AUAV21:
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_MINDPXV2:
|
||||
|
|
|
@ -420,7 +420,9 @@ private:
|
|||
#if AP_COMPASS_LSM303D_ENABLED
|
||||
DRIVER_LSM303D =1,
|
||||
#endif
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
DRIVER_AK8963 =2,
|
||||
#endif
|
||||
DRIVER_BMM150 =3,
|
||||
DRIVER_LSM9DS1 =4,
|
||||
DRIVER_LIS3MDL =5,
|
||||
|
|
|
@ -12,13 +12,17 @@
|
|||
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_AK8963.h"
|
||||
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
|
||||
#include <assert.h>
|
||||
#include <utility>
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_Compass_AK8963.h"
|
||||
#include <AP_InertialSensor/AP_InertialSensor_Invensense.h>
|
||||
|
||||
#define AK8963_I2C_ADDR 0x0c
|
||||
|
@ -400,3 +404,5 @@ uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const
|
|||
{
|
||||
return _bus->get_bus_id();
|
||||
}
|
||||
|
||||
#endif // AP_COMPASS_AK8963_ENABLED
|
||||
|
|
|
@ -1,5 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Compass_config.h"
|
||||
|
||||
#if AP_COMPASS_AK8963_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
@ -136,3 +140,5 @@ private:
|
|||
AuxiliaryBusSlave *_slave;
|
||||
bool _started;
|
||||
};
|
||||
|
||||
#endif // AP_COMPASS_AK8963_ENABLED
|
||||
|
|
|
@ -34,6 +34,10 @@
|
|||
#define AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED AP_COMPASS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_AK8963_ENABLED
|
||||
#define AP_COMPASS_AK8963_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_HMC5843_ENABLED
|
||||
#define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue