2012-11-11 20:26:20 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2011-02-14 00:27:07 -04:00
|
|
|
/*
|
2012-08-17 03:19:22 -03:00
|
|
|
* AP_Compass_HMC5843.cpp - Arduino Library for HMC5843 I2C magnetometer
|
|
|
|
* Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
|
|
|
*
|
|
|
|
* Sensor is conected to I2C port
|
|
|
|
* Sensor is initialized in Continuos mode (10Hz)
|
|
|
|
*
|
|
|
|
*/
|
2011-02-14 00:27:07 -04:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2011-02-14 00:27:07 -04:00
|
|
|
|
|
|
|
#include "AP_Compass_HMC5843.h"
|
2015-08-10 20:30:32 -03:00
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
|
|
|
#include <AP_InertialSensor/AuxiliaryBus.h>
|
2011-02-14 00:27:07 -04:00
|
|
|
|
2012-10-11 17:48:39 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-08-07 19:54:58 -03:00
|
|
|
#define HMC5843_I2C_ADDR 0x1E
|
2011-02-14 00:27:07 -04:00
|
|
|
#define ConfigRegA 0x00
|
|
|
|
#define ConfigRegB 0x01
|
|
|
|
#define magGain 0x20
|
|
|
|
#define PositiveBiasConfig 0x11
|
|
|
|
#define NegativeBiasConfig 0x12
|
|
|
|
#define NormalOperation 0x10
|
|
|
|
#define ModeRegister 0x02
|
|
|
|
#define ContinuousConversion 0x00
|
|
|
|
#define SingleConversion 0x01
|
|
|
|
|
2011-07-03 05:32:58 -03:00
|
|
|
// ConfigRegA valid sample averaging for 5883L
|
|
|
|
#define SampleAveraging_1 0x00
|
|
|
|
#define SampleAveraging_2 0x01
|
|
|
|
#define SampleAveraging_4 0x02
|
|
|
|
#define SampleAveraging_8 0x03
|
|
|
|
|
|
|
|
// ConfigRegA valid data output rates for 5883L
|
|
|
|
#define DataOutputRate_0_75HZ 0x00
|
|
|
|
#define DataOutputRate_1_5HZ 0x01
|
|
|
|
#define DataOutputRate_3HZ 0x02
|
|
|
|
#define DataOutputRate_7_5HZ 0x03
|
|
|
|
#define DataOutputRate_15HZ 0x04
|
|
|
|
#define DataOutputRate_30HZ 0x05
|
|
|
|
#define DataOutputRate_75HZ 0x06
|
|
|
|
|
2014-11-15 21:58:23 -04:00
|
|
|
// constructor
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_Compass_HMC5843::AP_Compass_HMC5843(Compass &compass, AP_HMC5843_SerialBus *bus) :
|
2014-11-15 21:58:23 -04:00
|
|
|
AP_Compass_Backend(compass),
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus(bus),
|
2015-04-24 02:12:41 -03:00
|
|
|
_retry_time(0),
|
2015-03-13 05:16:50 -03:00
|
|
|
_mag_x(0),
|
|
|
|
_mag_y(0),
|
|
|
|
_mag_z(0),
|
|
|
|
_mag_x_accum(0),
|
|
|
|
_mag_y_accum(0),
|
|
|
|
_mag_z_accum(0),
|
2015-02-23 19:17:44 -04:00
|
|
|
_accum_count(0),
|
2015-03-13 05:16:50 -03:00
|
|
|
_last_accum_time(0),
|
|
|
|
_compass_instance(0),
|
2015-02-23 19:17:44 -04:00
|
|
|
_product_id(0)
|
2014-11-15 21:58:23 -04:00
|
|
|
{}
|
|
|
|
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_Compass_HMC5843::~AP_Compass_HMC5843()
|
|
|
|
{
|
|
|
|
delete _bus;
|
|
|
|
}
|
|
|
|
|
2014-11-15 21:58:23 -04:00
|
|
|
// detect the sensor
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_HMC5843::detect_i2c(Compass &compass,
|
|
|
|
AP_HAL::I2CDriver *i2c)
|
|
|
|
{
|
|
|
|
AP_HMC5843_SerialBus *bus = new AP_HMC5843_SerialBus_I2C(i2c, HMC5843_I2C_ADDR);
|
|
|
|
if (!bus)
|
|
|
|
return nullptr;
|
|
|
|
return _detect(compass, bus);
|
|
|
|
}
|
|
|
|
|
2015-08-10 20:30:32 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_HMC5843::detect_mpu6000(Compass &compass)
|
|
|
|
{
|
|
|
|
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
|
|
|
AP_HMC5843_SerialBus *bus = new AP_HMC5843_SerialBus_MPU6000(ins, HMC5843_I2C_ADDR);
|
|
|
|
if (!bus)
|
|
|
|
return nullptr;
|
|
|
|
return _detect(compass, bus);
|
|
|
|
}
|
|
|
|
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_HMC5843::_detect(Compass &compass,
|
|
|
|
AP_HMC5843_SerialBus *bus)
|
2014-11-15 21:58:23 -04:00
|
|
|
{
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus);
|
|
|
|
if (!sensor) {
|
|
|
|
delete bus;
|
|
|
|
return nullptr;
|
2014-11-15 21:58:23 -04:00
|
|
|
}
|
|
|
|
if (!sensor->init()) {
|
|
|
|
delete sensor;
|
2015-08-07 19:54:58 -03:00
|
|
|
return nullptr;
|
2014-11-15 21:58:23 -04:00
|
|
|
}
|
2015-08-07 19:54:58 -03:00
|
|
|
|
2014-11-15 21:58:23 -04:00
|
|
|
return sensor;
|
|
|
|
}
|
|
|
|
|
2011-07-09 09:10:00 -03:00
|
|
|
// read_register - read a register value
|
2011-12-28 05:31:36 -04:00
|
|
|
bool AP_Compass_HMC5843::read_register(uint8_t address, uint8_t *value)
|
2011-07-09 09:10:00 -03:00
|
|
|
{
|
2015-08-07 19:54:58 -03:00
|
|
|
if (_bus->register_read(address, value) != 0) {
|
2015-11-19 23:09:17 -04:00
|
|
|
_retry_time = AP_HAL::millis() + 1000;
|
2012-08-17 03:19:22 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
2011-07-09 09:10:00 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// write_register - update a register value
|
2012-10-11 17:48:39 -03:00
|
|
|
bool AP_Compass_HMC5843::write_register(uint8_t address, uint8_t value)
|
2011-07-09 09:10:00 -03:00
|
|
|
{
|
2015-08-07 19:54:58 -03:00
|
|
|
if (_bus->register_write(address, value) != 0) {
|
2015-11-19 23:09:17 -04:00
|
|
|
_retry_time = AP_HAL::millis() + 1000;
|
2012-08-17 03:19:22 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
2011-07-09 09:10:00 -03:00
|
|
|
}
|
|
|
|
|
2011-08-13 05:17:25 -03:00
|
|
|
// Read Sensor data
|
|
|
|
bool AP_Compass_HMC5843::read_raw()
|
|
|
|
{
|
2015-08-10 19:24:56 -03:00
|
|
|
struct AP_HMC5843_SerialBus::raw_value rv;
|
2012-08-17 03:19:22 -03:00
|
|
|
|
2015-08-10 20:30:32 -03:00
|
|
|
if (_bus->read_raw(&rv) != 0) {
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus->set_high_speed(false);
|
2015-11-19 23:09:17 -04:00
|
|
|
_retry_time = AP_HAL::millis() + 1000;
|
2012-08-17 03:19:22 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
int16_t rx, ry, rz;
|
2015-08-10 19:24:56 -03:00
|
|
|
rx = (((int16_t)rv.val[0]) << 8) | rv.val[1];
|
2015-02-23 19:17:44 -04:00
|
|
|
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
2015-08-10 19:24:56 -03:00
|
|
|
rz = (((int16_t)rv.val[2]) << 8) | rv.val[3];
|
|
|
|
ry = (((int16_t)rv.val[4]) << 8) | rv.val[5];
|
2012-08-17 03:19:22 -03:00
|
|
|
} else {
|
2015-08-10 19:24:56 -03:00
|
|
|
ry = (((int16_t)rv.val[2]) << 8) | rv.val[3];
|
|
|
|
rz = (((int16_t)rv.val[4]) << 8) | rv.val[5];
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
if (rx == -4096 || ry == -4096 || rz == -4096) {
|
|
|
|
// no valid data available
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2012-08-26 00:42:00 -03:00
|
|
|
_mag_x = -rx;
|
|
|
|
_mag_y = ry;
|
|
|
|
_mag_z = -rz;
|
2012-08-17 03:19:22 -03:00
|
|
|
|
|
|
|
return true;
|
2011-08-13 05:17:25 -03:00
|
|
|
}
|
|
|
|
|
2011-07-03 05:32:58 -03:00
|
|
|
|
2012-08-26 00:42:00 -03:00
|
|
|
// accumulate a reading from the magnetometer
|
|
|
|
void AP_Compass_HMC5843::accumulate(void)
|
|
|
|
{
|
2013-10-07 21:10:53 -03:00
|
|
|
if (!_initialised) {
|
|
|
|
// someone has tried to enable a compass for the first time
|
|
|
|
// mid-flight .... we can't do that yet (especially as we won't
|
|
|
|
// have the right orientation!)
|
|
|
|
return;
|
|
|
|
}
|
2015-07-23 07:53:50 -03:00
|
|
|
|
2015-11-19 23:09:17 -04:00
|
|
|
uint32_t tnow = AP_HAL::micros();
|
2015-07-31 01:59:38 -03:00
|
|
|
if (_accum_count != 0 && (tnow - _last_accum_time) < 13333) {
|
|
|
|
// the compass gets new data at 75Hz
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!_bus_sem->take(1)) {
|
|
|
|
// the bus is busy - try again later
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
bool result = read_raw();
|
|
|
|
_bus_sem->give();
|
|
|
|
|
|
|
|
if (result) {
|
|
|
|
// the _mag_N values are in the range -2048 to 2047, so we can
|
|
|
|
// accumulate up to 15 of them in an int16_t. Let's make it 14
|
|
|
|
// for ease of calculation. We expect to do reads at 10Hz, and
|
|
|
|
// we get new data at most 75Hz, so we don't expect to
|
|
|
|
// accumulate more than 8 before a read
|
|
|
|
// get raw_field - sensor frame, uncorrected
|
|
|
|
Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);
|
2015-09-29 12:01:30 -03:00
|
|
|
raw_field *= _gain_multiple;
|
2015-07-31 01:59:38 -03:00
|
|
|
|
|
|
|
// rotate raw_field from sensor frame to body frame
|
|
|
|
rotate_field(raw_field, _compass_instance);
|
|
|
|
|
|
|
|
// publish raw_field (uncorrected point sample) for calibration use
|
|
|
|
publish_raw_field(raw_field, tnow, _compass_instance);
|
|
|
|
|
|
|
|
// correct raw_field for known errors
|
|
|
|
correct_field(raw_field, _compass_instance);
|
|
|
|
|
|
|
|
// publish raw_field (corrected point sample) for EKF use
|
|
|
|
publish_unfiltered_field(raw_field, tnow, _compass_instance);
|
|
|
|
|
2015-09-02 19:32:11 -03:00
|
|
|
_mag_x_accum += raw_field.x;
|
|
|
|
_mag_y_accum += raw_field.y;
|
|
|
|
_mag_z_accum += raw_field.z;
|
2015-07-31 01:59:38 -03:00
|
|
|
_accum_count++;
|
|
|
|
if (_accum_count == 14) {
|
|
|
|
_mag_x_accum /= 2;
|
|
|
|
_mag_y_accum /= 2;
|
|
|
|
_mag_z_accum /= 2;
|
|
|
|
_accum_count = 7;
|
|
|
|
}
|
|
|
|
_last_accum_time = tnow;
|
|
|
|
}
|
2012-08-26 00:42:00 -03:00
|
|
|
}
|
|
|
|
|
2011-12-28 05:31:36 -04:00
|
|
|
|
|
|
|
/*
|
2012-08-17 03:19:22 -03:00
|
|
|
* re-initialise after a IO error
|
2011-12-28 05:31:36 -04:00
|
|
|
*/
|
|
|
|
bool AP_Compass_HMC5843::re_initialise()
|
|
|
|
{
|
2012-08-17 03:19:22 -03:00
|
|
|
if (!write_register(ConfigRegA, _base_config) ||
|
|
|
|
!write_register(ConfigRegB, magGain) ||
|
|
|
|
!write_register(ModeRegister, ContinuousConversion))
|
|
|
|
return false;
|
|
|
|
return true;
|
2011-12-28 05:31:36 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-07-22 12:09:25 -03:00
|
|
|
bool AP_Compass_HMC5843::_detect_version()
|
|
|
|
{
|
|
|
|
_base_config = 0x0;
|
|
|
|
|
|
|
|
if (!write_register(ConfigRegA, SampleAveraging_8<<5 | DataOutputRate_75HZ<<2 | NormalOperation) ||
|
|
|
|
!read_register(ConfigRegA, &_base_config)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (_base_config == (SampleAveraging_8<<5 | DataOutputRate_75HZ<<2 | NormalOperation)) {
|
|
|
|
/* a 5883L supports the sample averaging config */
|
|
|
|
_product_id = AP_COMPASS_TYPE_HMC5883L;
|
|
|
|
return true;
|
|
|
|
} else if (_base_config == (NormalOperation | DataOutputRate_75HZ<<2)) {
|
|
|
|
_product_id = AP_COMPASS_TYPE_HMC5843;
|
|
|
|
return true;
|
|
|
|
} else {
|
|
|
|
/* not behaving like either supported compass type */
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-02-14 00:27:07 -04:00
|
|
|
// Public Methods //////////////////////////////////////////////////////////////
|
2012-08-17 03:19:22 -03:00
|
|
|
bool
|
2011-06-28 13:30:42 -03:00
|
|
|
AP_Compass_HMC5843::init()
|
2011-02-14 00:27:07 -04:00
|
|
|
{
|
2012-10-11 17:48:39 -03:00
|
|
|
uint8_t calibration_gain = 0x20;
|
2012-08-17 03:19:22 -03:00
|
|
|
uint16_t expected_x = 715;
|
|
|
|
uint16_t expected_yz = 715;
|
2015-09-29 12:01:30 -03:00
|
|
|
_gain_multiple = (1.0f / 1300) * 1000;
|
2012-08-17 03:19:22 -03:00
|
|
|
|
2015-08-10 15:28:05 -03:00
|
|
|
_bus_sem = _bus->get_semaphore();
|
2014-11-13 07:30:20 -04:00
|
|
|
hal.scheduler->suspend_timer_procs();
|
2012-08-17 03:19:22 -03:00
|
|
|
|
2015-08-10 20:30:32 -03:00
|
|
|
if (!_bus_sem || !_bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("HMC5843: Unable to get bus semaphore\n");
|
2015-08-10 20:30:32 -03:00
|
|
|
goto fail_sem;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!_bus->configure()) {
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("HMC5843: Could not configure the bus\n");
|
2015-08-10 20:30:32 -03:00
|
|
|
goto errout;
|
2013-01-09 05:42:20 -04:00
|
|
|
}
|
2013-01-04 18:26:26 -04:00
|
|
|
|
2015-07-22 12:09:25 -03:00
|
|
|
if (!_detect_version()) {
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("HMC5843: Could not detect version\n");
|
2015-07-22 12:09:25 -03:00
|
|
|
goto errout;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
2015-07-22 12:09:25 -03:00
|
|
|
|
|
|
|
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
2012-08-17 03:19:22 -03:00
|
|
|
calibration_gain = 0x60;
|
2014-01-22 01:07:50 -04:00
|
|
|
/*
|
|
|
|
note that the HMC5883 datasheet gives the x and y expected
|
|
|
|
values as 766 and the z as 713. Experiments have shown the x
|
|
|
|
axis is around 766, and the y and z closer to 713.
|
|
|
|
*/
|
2012-08-17 03:19:22 -03:00
|
|
|
expected_x = 766;
|
|
|
|
expected_yz = 713;
|
2015-09-29 12:01:30 -03:00
|
|
|
_gain_multiple = (1.0f / 1090) * 1000;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
|
2015-08-24 11:21:34 -03:00
|
|
|
if (!_calibrate(calibration_gain, expected_x, expected_yz)) {
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("HMC5843: Could not calibrate sensor\n");
|
2015-07-22 12:31:50 -03:00
|
|
|
goto errout;
|
|
|
|
}
|
|
|
|
|
|
|
|
// leave test mode
|
|
|
|
if (!re_initialise()) {
|
|
|
|
goto errout;
|
|
|
|
}
|
|
|
|
|
2015-08-10 20:30:32 -03:00
|
|
|
if (!_bus->start_measurements()) {
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("HMC5843: Could not start measurements on bus\n");
|
2015-08-10 20:30:32 -03:00
|
|
|
goto errout;
|
|
|
|
}
|
2015-08-10 16:50:29 -03:00
|
|
|
_initialised = true;
|
2015-08-10 20:30:32 -03:00
|
|
|
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus_sem->give();
|
2015-08-10 16:50:29 -03:00
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
|
|
|
|
// perform an initial read
|
2015-07-22 12:31:50 -03:00
|
|
|
read();
|
|
|
|
|
|
|
|
#if 0
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("CalX: %.2f CalY: %.2f CalZ: %.2f\n",
|
2015-07-23 10:21:31 -03:00
|
|
|
_scaling[0], _scaling[1], _scaling[2]);
|
2015-07-22 12:31:50 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
_compass_instance = register_compass();
|
|
|
|
set_dev_id(_compass_instance, _product_id);
|
|
|
|
|
2015-08-17 21:09:52 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
|
|
|
set_external(_compass_instance, true);
|
|
|
|
#endif
|
|
|
|
|
2015-07-22 12:31:50 -03:00
|
|
|
return true;
|
|
|
|
|
2015-08-10 16:50:29 -03:00
|
|
|
errout:
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus_sem->give();
|
2015-08-10 20:30:32 -03:00
|
|
|
fail_sem:
|
2015-07-22 12:31:50 -03:00
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_Compass_HMC5843::_calibrate(uint8_t calibration_gain,
|
|
|
|
uint16_t expected_x,
|
2015-08-24 11:21:34 -03:00
|
|
|
uint16_t expected_yz)
|
2015-07-22 12:31:50 -03:00
|
|
|
{
|
|
|
|
int numAttempts = 0, good_count = 0;
|
|
|
|
bool success = false;
|
2012-08-17 03:19:22 -03:00
|
|
|
|
2015-07-23 07:53:50 -03:00
|
|
|
while (success == 0 && numAttempts < 25 && good_count < 5)
|
2012-08-17 03:19:22 -03:00
|
|
|
{
|
|
|
|
numAttempts++;
|
|
|
|
|
|
|
|
// force positiveBias (compass should return 715 for all channels)
|
|
|
|
if (!write_register(ConfigRegA, PositiveBiasConfig))
|
2015-07-23 07:53:50 -03:00
|
|
|
continue; // compass not responding on the bus
|
|
|
|
|
2012-10-11 17:48:39 -03:00
|
|
|
hal.scheduler->delay(50);
|
2012-08-17 03:19:22 -03:00
|
|
|
|
|
|
|
// set gains
|
|
|
|
if (!write_register(ConfigRegB, calibration_gain) ||
|
|
|
|
!write_register(ModeRegister, SingleConversion))
|
|
|
|
continue;
|
|
|
|
|
|
|
|
// read values from the compass
|
2012-10-11 17:48:39 -03:00
|
|
|
hal.scheduler->delay(50);
|
2012-08-17 03:19:22 -03:00
|
|
|
if (!read_raw())
|
|
|
|
continue; // we didn't read valid values
|
|
|
|
|
2012-10-11 17:48:39 -03:00
|
|
|
hal.scheduler->delay(10);
|
2012-08-17 03:19:22 -03:00
|
|
|
|
|
|
|
float cal[3];
|
|
|
|
|
2015-10-25 17:10:41 -03:00
|
|
|
// hal.console->printf("mag %d %d %d\n", _mag_x, _mag_y, _mag_z);
|
2015-07-23 07:53:50 -03:00
|
|
|
|
2013-01-10 14:42:24 -04:00
|
|
|
cal[0] = fabsf(expected_x / (float)_mag_x);
|
|
|
|
cal[1] = fabsf(expected_yz / (float)_mag_y);
|
|
|
|
cal[2] = fabsf(expected_yz / (float)_mag_z);
|
2012-08-17 03:19:22 -03:00
|
|
|
|
2015-10-25 17:10:41 -03:00
|
|
|
// hal.console->printf("cal=%.2f %.2f %.2f\n", cal[0], cal[1], cal[2]);
|
2014-01-22 01:07:50 -04:00
|
|
|
|
|
|
|
// we throw away the first two samples as the compass may
|
|
|
|
// still be changing its state from the application of the
|
|
|
|
// strap excitation. After that we accept values in a
|
|
|
|
// reasonable range
|
2015-07-23 07:53:50 -03:00
|
|
|
|
2015-07-23 10:29:39 -03:00
|
|
|
if (numAttempts <= 2) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
2015-07-23 07:52:02 -03:00
|
|
|
#define IS_CALIBRATION_VALUE_VALID(val) (val > 0.7f && val < 1.35f)
|
|
|
|
|
2015-07-23 10:29:39 -03:00
|
|
|
if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&
|
2015-07-23 07:52:02 -03:00
|
|
|
IS_CALIBRATION_VALUE_VALID(cal[1]) &&
|
|
|
|
IS_CALIBRATION_VALUE_VALID(cal[2])) {
|
2015-10-25 17:10:41 -03:00
|
|
|
// hal.console->printf("car=%.2f %.2f %.2f good\n", cal[0], cal[1], cal[2]);
|
2012-08-17 03:19:22 -03:00
|
|
|
good_count++;
|
2015-07-23 10:29:39 -03:00
|
|
|
|
2015-07-23 10:21:31 -03:00
|
|
|
_scaling[0] += cal[0];
|
|
|
|
_scaling[1] += cal[1];
|
|
|
|
_scaling[2] += cal[2];
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
2011-08-13 05:17:25 -03:00
|
|
|
|
2015-07-23 07:52:02 -03:00
|
|
|
#undef IS_CALIBRATION_VALUE_VALID
|
|
|
|
|
2011-08-13 05:17:25 -03:00
|
|
|
#if 0
|
2012-08-17 03:19:22 -03:00
|
|
|
/* useful for debugging */
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("MagX: %d MagY: %d MagZ: %d\n", (int)_mag_x, (int)_mag_y, (int)_mag_z);
|
|
|
|
hal.console->printf("CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);
|
2011-08-13 05:17:25 -03:00
|
|
|
#endif
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (good_count >= 5) {
|
2015-09-29 11:48:46 -03:00
|
|
|
_scaling[0] = _scaling[0] / good_count;
|
|
|
|
_scaling[1] = _scaling[1] / good_count;
|
|
|
|
_scaling[2] = _scaling[2] / good_count;
|
2012-08-17 03:19:22 -03:00
|
|
|
success = true;
|
|
|
|
} else {
|
|
|
|
/* best guess */
|
2015-07-23 10:21:31 -03:00
|
|
|
_scaling[0] = 1.0;
|
|
|
|
_scaling[1] = 1.0;
|
|
|
|
_scaling[2] = 1.0;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return success;
|
2011-02-14 00:27:07 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Read Sensor data
|
2015-02-23 19:17:44 -04:00
|
|
|
void AP_Compass_HMC5843::read()
|
2011-02-14 00:27:07 -04:00
|
|
|
{
|
2012-08-17 03:19:22 -03:00
|
|
|
if (!_initialised) {
|
|
|
|
// someone has tried to enable a compass for the first time
|
|
|
|
// mid-flight .... we can't do that yet (especially as we won't
|
|
|
|
// have the right orientation!)
|
2015-02-23 19:17:44 -04:00
|
|
|
return;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
2015-02-23 19:17:44 -04:00
|
|
|
if (_retry_time != 0) {
|
2015-11-19 23:09:17 -04:00
|
|
|
if (AP_HAL::millis() < _retry_time) {
|
2015-02-23 19:17:44 -04:00
|
|
|
return;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
if (!re_initialise()) {
|
2015-11-19 23:09:17 -04:00
|
|
|
_retry_time = AP_HAL::millis() + 1000;
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus->set_high_speed(false);
|
2015-02-23 19:17:44 -04:00
|
|
|
return;
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-07-23 07:53:50 -03:00
|
|
|
if (_accum_count == 0) {
|
|
|
|
accumulate();
|
2015-02-23 19:17:44 -04:00
|
|
|
if (_retry_time != 0) {
|
2015-08-07 19:54:58 -03:00
|
|
|
_bus->set_high_speed(false);
|
2015-07-23 07:53:50 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2012-08-26 00:42:00 -03:00
|
|
|
|
2015-07-23 10:21:31 -03:00
|
|
|
Vector3f field(_mag_x_accum * _scaling[0],
|
|
|
|
_mag_y_accum * _scaling[1],
|
|
|
|
_mag_z_accum * _scaling[2]);
|
2015-02-23 19:17:44 -04:00
|
|
|
field /= _accum_count;
|
|
|
|
|
2015-07-23 07:53:50 -03:00
|
|
|
_accum_count = 0;
|
|
|
|
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
|
2012-08-17 03:19:22 -03:00
|
|
|
|
|
|
|
// rotate to the desired orientation
|
2015-02-23 19:17:44 -04:00
|
|
|
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
|
|
|
field.rotate(ROTATION_YAW_90);
|
2012-08-17 03:19:22 -03:00
|
|
|
}
|
2013-01-13 01:02:49 -04:00
|
|
|
|
2015-03-18 19:17:12 -03:00
|
|
|
publish_filtered_field(field, _compass_instance);
|
2015-02-23 19:17:44 -04:00
|
|
|
_retry_time = 0;
|
2011-02-14 00:27:07 -04:00
|
|
|
}
|
2015-08-07 19:54:58 -03:00
|
|
|
|
2015-08-10 20:30:32 -03:00
|
|
|
/* I2C implementation of the HMC5843 */
|
2015-08-07 19:54:58 -03:00
|
|
|
AP_HMC5843_SerialBus_I2C::AP_HMC5843_SerialBus_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr)
|
|
|
|
: _i2c(i2c)
|
|
|
|
, _addr(addr)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_HMC5843_SerialBus_I2C::set_high_speed(bool val)
|
|
|
|
{
|
|
|
|
_i2c->setHighSpeed(val);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_I2C::register_read(uint8_t reg, uint8_t *buf, uint8_t size)
|
|
|
|
{
|
|
|
|
return _i2c->readRegisters(_addr, reg, size, buf);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_I2C::register_write(uint8_t reg, uint8_t val)
|
|
|
|
{
|
|
|
|
return _i2c->writeRegister(_addr, reg, val);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::Semaphore* AP_HMC5843_SerialBus_I2C::get_semaphore()
|
|
|
|
{
|
|
|
|
return _i2c->get_semaphore();
|
|
|
|
}
|
2015-08-10 20:30:32 -03:00
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_I2C::read_raw(struct raw_value *rv)
|
|
|
|
{
|
|
|
|
return register_read(0x03, (uint8_t*)rv, sizeof(*rv));
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/* MPU6000 implementation of the HMC5843 */
|
|
|
|
AP_HMC5843_SerialBus_MPU6000::AP_HMC5843_SerialBus_MPU6000(AP_InertialSensor &ins,
|
|
|
|
uint8_t addr)
|
|
|
|
{
|
|
|
|
// Only initialize members. Fails are handled by configure or while
|
|
|
|
// getting the semaphore
|
2015-10-06 18:51:46 -03:00
|
|
|
_bus = ins.get_auxiliary_bus(HAL_INS_MPU60XX_SPI);
|
2015-08-10 20:30:32 -03:00
|
|
|
if (!_bus)
|
|
|
|
return;
|
|
|
|
_slave = _bus->request_next_slave(addr);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HMC5843_SerialBus_MPU6000::~AP_HMC5843_SerialBus_MPU6000()
|
|
|
|
{
|
|
|
|
/* After started it's owned by AuxiliaryBus */
|
|
|
|
if (!_started)
|
|
|
|
delete _slave;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_HMC5843_SerialBus_MPU6000::configure()
|
|
|
|
{
|
|
|
|
if (!_bus || !_slave)
|
|
|
|
return false;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_HMC5843_SerialBus_MPU6000::set_high_speed(bool val)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_MPU6000::register_read(uint8_t reg, uint8_t *buf, uint8_t size)
|
|
|
|
{
|
|
|
|
return _slave->passthrough_read(reg, buf, size) == size ? 0 : 1;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_MPU6000::register_write(uint8_t reg, uint8_t val)
|
|
|
|
{
|
|
|
|
return _slave->passthrough_write(reg, val) >= 0 ? 0 : 1;
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::Semaphore* AP_HMC5843_SerialBus_MPU6000::get_semaphore()
|
|
|
|
{
|
|
|
|
return _bus ? _bus->get_semaphore() : nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AP_HMC5843_SerialBus_MPU6000::read_raw(struct raw_value *rv)
|
|
|
|
{
|
|
|
|
if (_started)
|
|
|
|
return _slave->read((uint8_t*)rv) >= 0 ? 0 : 1;
|
|
|
|
|
|
|
|
return _slave->passthrough_read(0x03, (uint8_t*)rv, sizeof(*rv)) >= 0 ? 0 : 1;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_HMC5843_SerialBus_MPU6000::start_measurements()
|
|
|
|
{
|
|
|
|
if (_bus->register_periodic_read(_slave, 0x03, sizeof(struct raw_value)) < 0)
|
|
|
|
return false;
|
|
|
|
|
|
|
|
_started = true;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|