AP_Compass: add ppro support

disable lis3mdl for now
This commit is contained in:
Kevin Lopez Alvarez 2017-07-15 15:13:44 +10:00 committed by Andrew Tridgell
parent 34c977f046
commit 1467daee2a
3 changed files with 9 additions and 4 deletions

View File

@ -554,7 +554,8 @@ void Compass::_detect_backends(void)
case AP_BoardConfig::PX4_BOARD_AUAV21:
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
case AP_BoardConfig::PX4_BOARD_PIXRACER: {
case AP_BoardConfig::PX4_BOARD_PIXRACER:
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:{
bool both_i2c_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
// external i2c bus
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR),
@ -640,6 +641,10 @@ void Compass::_detect_backends(void)
AP_Compass_HMC5843::name, false);
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
AP_Compass_AK8963::name, false);
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
AP_Compass_AK8963::name, false);
break;
case AP_BoardConfig::PX4_BOARD_PHMINI:

View File

@ -49,7 +49,7 @@
extern const AP_HAL::HAL &hal;
AP_Compass_Backend *AP_Compass_LIS3MDL::probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{

View File

@ -16,7 +16,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>
#include "AP_Compass.h"
@ -31,7 +31,7 @@ class AP_Compass_LIS3MDL : public AP_Compass_Backend
{
public:
static AP_Compass_Backend *probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external = false,
enum Rotation rotation = ROTATION_NONE);