mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Compass: enabled AK8963 on PX4
This commit is contained in:
parent
a06137bb68
commit
974827aa82
@ -503,6 +503,10 @@ void Compass::_detect_backends(void)
|
|||||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
|
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
|
||||||
AP_Compass_LSM303D::name, false);
|
AP_Compass_LSM303D::name, false);
|
||||||
}
|
}
|
||||||
|
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
|
||||||
|
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||||
|
AP_Compass_AK8963::name, false);
|
||||||
|
}
|
||||||
// also add any px4 level drivers (for canbus magnetometers)
|
// also add any px4 level drivers (for canbus magnetometers)
|
||||||
_add_backend(AP_Compass_PX4::detect(*this), nullptr, false);
|
_add_backend(AP_Compass_PX4::detect(*this), nullptr, false);
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
||||||
|
@ -18,8 +18,6 @@
|
|||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "AP_Compass_AK8963.h"
|
#include "AP_Compass_AK8963.h"
|
||||||
#include <AP_InertialSensor/AP_InertialSensor_MPU9250.h>
|
#include <AP_InertialSensor/AP_InertialSensor_MPU9250.h>
|
||||||
|
|
||||||
@ -426,4 +424,3 @@ bool AP_AK8963_BusDriver_Auxiliary::start_measurements()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
Loading…
Reference in New Issue
Block a user