AP_Compass: remove Qualcomm board support

This commit is contained in:
Francisco Ferreira 2018-05-11 13:26:51 +01:00 committed by Andrew Tridgell
parent f8756fac6b
commit 0a3af28d17
6 changed files with 1 additions and 263 deletions

View File

@ -14,8 +14,6 @@
#include "AP_Compass_IST8310.h"
#include "AP_Compass_LSM303D.h"
#include "AP_Compass_LSM9DS1.h"
#include "AP_Compass_QURT.h"
#include "AP_Compass_qflight.h"
#include "AP_Compass_LIS3MDL.h"
#include "AP_Compass_AK09916.h"
#include "AP_Compass_QMC5883L.h"
@ -434,7 +432,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Param: TYPEMASK
// @DisplayName: Compass disable driver type mask
// @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
// @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,10:QFLIGHT,11:UAVCAN,12:QMC5883
// @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883
// @User: Advanced
AP_GROUPINFO("TYPEMASK", 33, Compass, _driver_type_mask, 0),
@ -777,14 +775,10 @@ void Compass::_detect_backends(void)
break;
}
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
ADD_BACKEND(DRIVER_QFLIGHT, AP_Compass_QURT::detect(*this), nullptr, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
AP_Compass_HMC5843::name, false);
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0), AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QFLIGHT
ADD_BACKEND(DRIVER_QFLIGHT, AP_Compass_QFLIGHT::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
AP_Compass_HMC5843::name, true);

View File

@ -370,7 +370,6 @@ private:
DRIVER_IST8310 =7,
DRIVER_ICM20948 =8,
DRIVER_MMC3416 =9,
DRIVER_QFLIGHT =10,
DRIVER_UAVCAN =11,
DRIVER_QMC5883 =12,
DRIVER_SITL =13,

View File

@ -1,93 +0,0 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
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_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
#include "AP_Compass_QURT.h"
#include <AP_InertialSensor/AP_InertialSensor_QURT.h>
extern const AP_HAL::HAL& hal;
// Public Methods //////////////////////////////////////////////////////////////
// constructor
AP_Compass_QURT::AP_Compass_QURT(Compass &compass):
AP_Compass_Backend(compass)
{
}
// detect the sensor
AP_Compass_Backend *AP_Compass_QURT::detect(Compass &compass)
{
AP_Compass_QURT *sensor = new AP_Compass_QURT(compass);
if (sensor == nullptr) {
return nullptr;
}
if (!sensor->init()) {
delete sensor;
return nullptr;
}
return sensor;
}
bool AP_Compass_QURT::init(void)
{
instance = register_compass();
// publish a zero as a hack
publish_filtered_field(Vector3f(), instance);
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_QURT::timer_update, void));
return true;
}
void AP_Compass_QURT::read(void)
{
// avoid division by zero if we haven't received any mag reports
if (count != 0) {
sum /= count;
publish_filtered_field(sum, instance);
sum.zero();
count = 0;
}
}
void AP_Compass_QURT::timer_update(void)
{
// cope the data
struct mpu9x50_data data;
if (mpu9250_mag_buffer == nullptr || !mpu9250_mag_buffer->pop(data)) {
return;
}
Vector3f raw_field(data.mag_raw[0],
data.mag_raw[1],
-data.mag_raw[2]);
// rotate raw_field from sensor frame to body frame
rotate_field(raw_field, instance);
// publish raw_field (uncorrected point sample) for calibration use
publish_raw_field(raw_field, instance);
// correct raw_field for known errors
correct_field(raw_field, instance);
// accumulate into averaging filter
sum += raw_field;
count++;
}
#endif // CONFIG_HAL_BOARD

View File

@ -1,25 +0,0 @@
#pragma once
#include "AP_Compass.h"
#include "AP_Compass_Backend.h"
class AP_Compass_QURT : public AP_Compass_Backend
{
public:
void read(void) override;
AP_Compass_QURT(Compass &compass);
// detect the sensor
static AP_Compass_Backend *detect(Compass &compass);
private:
bool init(void);
void timer_update(void);
uint8_t instance;
Vector3f sum;
uint32_t count;
};

View File

@ -1,105 +0,0 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
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_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
#include "AP_Compass_qflight.h"
#include <AP_HAL_Linux/qflight/qflight_util.h>
#include <AP_HAL_Linux/qflight/qflight_dsp.h>
#include "AP_Compass_qflight.h"
#include <unistd.h>
extern const AP_HAL::HAL& hal;
// constructor
AP_Compass_QFLIGHT::AP_Compass_QFLIGHT(Compass &compass):
AP_Compass_Backend(compass)
{
}
// detect the sensor
AP_Compass_Backend *AP_Compass_QFLIGHT::detect(Compass &compass)
{
AP_Compass_QFLIGHT *sensor = new AP_Compass_QFLIGHT(compass);
if (sensor == nullptr) {
return nullptr;
}
if (!sensor->init()) {
delete sensor;
return nullptr;
}
return sensor;
}
bool AP_Compass_QFLIGHT::init(void)
{
instance = register_compass();
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_QFLIGHT::timer_update, void));
// give time for at least one sample
hal.scheduler->delay(100);
return true;
}
void AP_Compass_QFLIGHT::read(void)
{
if (count > 0) {
publish_filtered_field(sum/count, instance);
sum.zero();
count = 0;
}
}
void AP_Compass_QFLIGHT::timer_update(void)
{
uint32_t now = AP_HAL::millis();
if (now - last_check_ms < 25) {
return;
}
last_check_ms = now;
if (magbuf == nullptr) {
magbuf = QFLIGHT_RPC_ALLOCATE(DSPBuffer::MAG);
if (magbuf == nullptr) {
AP_HAL::panic("unable to allocate MAG buffer");
}
}
int ret = qflight_get_mag_data((uint8_t *)magbuf, sizeof(*magbuf));
if (ret != 0) {
return;
}
for (uint16_t i=0; i<magbuf->num_samples; i++) {
DSPBuffer::MAG::BUF &b = magbuf->buf[i];
// get raw_field - sensor frame, uncorrected
Vector3f raw_field(b.mag_raw[0], b.mag_raw[1], -b.mag_raw[2]);
// rotate raw_field from sensor frame to body frame
rotate_field(raw_field, instance);
// publish raw_field (uncorrected point sample) for calibration use
publish_raw_field(raw_field, instance);
// correct raw_field for known errors
correct_field(raw_field, instance);
// accumulate into averaging filter
sum += raw_field;
count++;
}
}
#endif // CONFIG_HAL_BOARD_SUBTYPE

View File

@ -1,32 +0,0 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
#include <AP_HAL_Linux/qflight/qflight_buffer.h>
#include "AP_Compass.h"
#include "AP_Compass_Backend.h"
class AP_Compass_QFLIGHT : public AP_Compass_Backend
{
public:
bool init(void);
void read(void);
AP_Compass_QFLIGHT(Compass &compass);
// detect the sensor
static AP_Compass_Backend *detect(Compass &compass);
private:
void timer_update();
DSPBuffer::MAG *magbuf;
uint8_t instance;
Vector3f sum;
uint32_t count;
uint32_t last_check_ms;
};
#endif // CONFIG_HAL_BOARD_SUBTYPE