2014-11-21 12:26:58 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-07-02 21:01:04 -03:00
|
|
|
|
2015-07-08 22:57:27 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
|
|
|
2014-11-21 12:26:58 -04:00
|
|
|
#include "AP_Compass_AK8963.h"
|
2015-08-15 19:49:52 -03:00
|
|
|
#include <AP_InertialSensor/AP_InertialSensor_MPU9250.h>
|
2014-11-21 12:26:58 -04:00
|
|
|
|
|
|
|
#define AK8963_I2C_ADDR 0x0c
|
|
|
|
|
|
|
|
#define AK8963_WIA 0x00
|
|
|
|
# define AK8963_Device_ID 0x48
|
|
|
|
|
|
|
|
#define AK8963_HXL 0x03
|
|
|
|
|
|
|
|
/* bit definitions for AK8963 CNTL1 */
|
|
|
|
#define AK8963_CNTL1 0x0A
|
2015-07-21 11:58:05 -03:00
|
|
|
# define AK8963_CONTINUOUS_MODE1 0x02
|
|
|
|
# define AK8963_CONTINUOUS_MODE2 0x06
|
|
|
|
# define AK8963_SELFTEST_MODE 0x08
|
|
|
|
# define AK8963_POWERDOWN_MODE 0x00
|
|
|
|
# define AK8963_FUSE_MODE 0x0f
|
2014-11-21 12:26:58 -04:00
|
|
|
# define AK8963_16BIT_ADC 0x10
|
|
|
|
# define AK8963_14BIT_ADC 0x00
|
|
|
|
|
|
|
|
#define AK8963_CNTL2 0x0B
|
|
|
|
# define AK8963_RESET 0x01
|
|
|
|
|
|
|
|
#define AK8963_ASAX 0x10
|
|
|
|
|
|
|
|
#define AK8963_DEBUG 0
|
|
|
|
#if AK8963_DEBUG
|
2015-07-02 10:37:37 -03:00
|
|
|
#include <stdio.h>
|
|
|
|
#define error(...) do { fprintf(stderr, __VA_ARGS__); } while (0)
|
2015-01-06 17:39:54 -04:00
|
|
|
#define ASSERT(x) assert(x)
|
2014-11-21 12:26:58 -04:00
|
|
|
#else
|
2015-07-02 10:37:37 -03:00
|
|
|
#define error(...) do { } while (0)
|
|
|
|
#ifndef ASSERT
|
2015-01-06 17:39:54 -04:00
|
|
|
#define ASSERT(x)
|
2014-11-21 12:26:58 -04:00
|
|
|
#endif
|
2015-07-02 10:37:37 -03:00
|
|
|
#endif
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-09-29 16:17:22 -03:00
|
|
|
#define AK8963_MILLIGAUSS_SCALE 10.0f
|
|
|
|
|
2014-11-21 12:26:58 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-07-06 14:50:59 -03:00
|
|
|
AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus) :
|
2015-07-02 10:37:37 -03:00
|
|
|
AP_Compass_Backend(compass),
|
|
|
|
_initialized(false),
|
|
|
|
_last_update_timestamp(0),
|
2015-07-06 14:50:59 -03:00
|
|
|
_last_accum_time(0),
|
|
|
|
_bus(bus)
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
2015-07-22 08:50:32 -03:00
|
|
|
_reset_filter();
|
2015-07-10 01:05:21 -03:00
|
|
|
}
|
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_AK8963::detect_mpu9250(Compass &compass, uint8_t mpu9250_instance)
|
2015-07-10 01:05:21 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
|
|
|
AP_AK8963_SerialBus *bus = new AP_AK8963_SerialBus_MPU9250(ins, AK8963_I2C_ADDR, mpu9250_instance);
|
2015-08-06 11:54:01 -03:00
|
|
|
if (!bus)
|
2015-07-10 01:05:21 -03:00
|
|
|
return nullptr;
|
2015-08-06 11:54:01 -03:00
|
|
|
return _detect(compass, bus);
|
2015-07-10 01:05:21 -03:00
|
|
|
}
|
|
|
|
|
2015-08-05 19:02:56 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_AK8963::detect_i2c(Compass &compass,
|
|
|
|
AP_HAL::I2CDriver *i2c,
|
|
|
|
uint8_t addr)
|
2015-07-10 01:05:21 -03:00
|
|
|
{
|
2015-08-06 11:54:01 -03:00
|
|
|
AP_AK8963_SerialBus *bus = new AP_AK8963_SerialBus_I2C(i2c, addr);
|
|
|
|
if (!bus)
|
|
|
|
return nullptr;
|
|
|
|
return _detect(compass, bus);
|
|
|
|
}
|
2015-07-10 01:05:21 -03:00
|
|
|
|
2015-09-28 17:46:19 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_AK8963::detect_mpu9250_i2c(Compass &compass,
|
|
|
|
AP_HAL::I2CDriver *i2c,
|
|
|
|
uint8_t addr)
|
|
|
|
{
|
|
|
|
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
|
|
|
ins.detect_backends();
|
|
|
|
return detect_i2c(compass, i2c, addr);
|
|
|
|
}
|
|
|
|
|
2015-08-06 11:54:01 -03:00
|
|
|
AP_Compass_Backend *AP_Compass_AK8963::_detect(Compass &compass,
|
|
|
|
AP_AK8963_SerialBus *bus)
|
|
|
|
{
|
|
|
|
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus);
|
2015-07-10 01:05:21 -03:00
|
|
|
if (sensor == nullptr) {
|
2015-08-06 11:54:01 -03:00
|
|
|
delete bus;
|
2015-07-10 01:05:21 -03:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
if (!sensor->init()) {
|
|
|
|
delete sensor;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
return sensor;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-08-06 11:54:01 -03:00
|
|
|
AP_Compass_AK8963::~AP_Compass_AK8963()
|
|
|
|
{
|
|
|
|
delete _bus;
|
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
/* stub to satisfy Compass API*/
|
|
|
|
void AP_Compass_AK8963::accumulate(void)
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::init()
|
2015-03-18 02:05:48 -03:00
|
|
|
{
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus_sem = _bus->get_semaphore();
|
2015-07-01 19:48:06 -03:00
|
|
|
|
2015-07-02 21:01:04 -03:00
|
|
|
hal.scheduler->suspend_timer_procs();
|
|
|
|
|
2015-07-06 14:50:59 -03:00
|
|
|
if (!_bus_sem->take(100)) {
|
|
|
|
hal.console->printf("AK8963: Unable to get bus semaphore");
|
2015-07-02 21:01:04 -03:00
|
|
|
goto fail_sem;
|
|
|
|
}
|
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
if (!_check_id()) {
|
|
|
|
hal.console->printf("AK8963: Wrong id\n");
|
2015-07-02 21:01:04 -03:00
|
|
|
goto fail;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2015-07-01 19:48:06 -03:00
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
if (!_calibrate()) {
|
|
|
|
hal.console->printf("AK8963: Could not read calibration data\n");
|
2015-07-02 21:01:04 -03:00
|
|
|
goto fail;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2015-03-18 02:05:48 -03:00
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
if (!_setup_mode()) {
|
|
|
|
hal.console->printf("AK8963: Could not setup mode\n");
|
2015-07-02 21:01:04 -03:00
|
|
|
goto fail;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
if (!_bus->start_measurements()) {
|
2015-09-14 13:19:34 -03:00
|
|
|
hal.console->printf("AK8963: Could not start measurements\n");
|
2015-07-02 21:01:04 -03:00
|
|
|
goto fail;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
_initialized = true;
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
/* register the compass instance in the frontend */
|
|
|
|
_compass_instance = register_compass();
|
2015-07-10 01:05:21 -03:00
|
|
|
set_dev_id(_compass_instance, _bus->get_dev_id());
|
2015-07-02 10:37:37 -03:00
|
|
|
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));
|
2015-07-02 21:01:04 -03:00
|
|
|
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus_sem->give();
|
2015-07-02 10:37:37 -03:00
|
|
|
hal.scheduler->resume_timer_procs();
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
return true;
|
2015-07-02 21:01:04 -03:00
|
|
|
|
|
|
|
fail:
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus_sem->give();
|
2015-07-02 21:01:04 -03:00
|
|
|
fail_sem:
|
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
|
|
|
|
return false;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
void AP_Compass_AK8963::read()
|
2014-11-15 21:58:23 -04:00
|
|
|
{
|
2015-07-02 10:37:37 -03:00
|
|
|
if (!_initialized) {
|
|
|
|
return;
|
2014-11-15 21:58:23 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
if (_accum_count == 0) {
|
|
|
|
/* We're not ready to publish*/
|
|
|
|
return;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-31 13:27:03 -03:00
|
|
|
hal.scheduler->suspend_timer_procs();
|
2015-07-22 08:50:32 -03:00
|
|
|
auto field = _get_filtered_field();
|
2015-07-23 19:50:45 -03:00
|
|
|
|
2015-07-22 08:50:32 -03:00
|
|
|
_reset_filter();
|
2015-07-31 13:27:03 -03:00
|
|
|
hal.scheduler->resume_timer_procs();
|
2015-07-31 01:55:16 -03:00
|
|
|
publish_filtered_field(field, _compass_instance);
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-22 08:50:32 -03:00
|
|
|
Vector3f AP_Compass_AK8963::_get_filtered_field() const
|
|
|
|
{
|
|
|
|
Vector3f field(_mag_x_accum, _mag_y_accum, _mag_z_accum);
|
|
|
|
field /= _accum_count;
|
|
|
|
|
|
|
|
return field;
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Compass_AK8963::_reset_filter()
|
|
|
|
{
|
|
|
|
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
|
|
|
|
_accum_count = 0;
|
|
|
|
}
|
|
|
|
|
2015-07-23 19:50:45 -03:00
|
|
|
void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const
|
|
|
|
{
|
|
|
|
static const float ADC_16BIT_RESOLUTION = 0.15f;
|
|
|
|
|
|
|
|
field *= ADC_16BIT_RESOLUTION;
|
|
|
|
}
|
|
|
|
|
2015-07-22 08:50:32 -03:00
|
|
|
void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const
|
|
|
|
{
|
|
|
|
field.x *= _magnetometer_ASA[0];
|
|
|
|
field.y *= _magnetometer_ASA[1];
|
|
|
|
field.z *= _magnetometer_ASA[2];
|
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
void AP_Compass_AK8963::_update()
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
2015-07-31 11:57:12 -03:00
|
|
|
struct AP_AK8963_SerialBus::raw_value rv;
|
|
|
|
float mag_x, mag_y, mag_z;
|
2015-08-28 17:01:24 -03:00
|
|
|
// get raw_field - sensor frame, uncorrected
|
2015-09-03 08:26:54 -03:00
|
|
|
Vector3f raw_field;
|
2015-11-19 23:09:17 -04:00
|
|
|
uint32_t time_us = AP_HAL::micros();
|
2015-08-28 17:01:24 -03:00
|
|
|
|
2015-07-31 11:57:12 -03:00
|
|
|
|
2015-11-19 23:09:17 -04:00
|
|
|
if (AP_HAL::micros() - _last_update_timestamp < 10000) {
|
2015-07-31 11:57:12 -03:00
|
|
|
goto end;
|
2015-03-18 02:05:48 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
if (!_sem_take_nonblocking()) {
|
2015-07-31 11:57:12 -03:00
|
|
|
goto end;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-22 16:59:24 -03:00
|
|
|
_bus->read_raw(&rv);
|
|
|
|
|
|
|
|
/* Check for overflow. See AK8963's datasheet, section
|
|
|
|
* 6.4.3.6 - Magnetic Sensor Overflow. */
|
|
|
|
if ((rv.st2 & 0x08)) {
|
2015-07-31 11:57:12 -03:00
|
|
|
goto fail;
|
2015-07-22 16:59:24 -03:00
|
|
|
}
|
|
|
|
|
2015-07-31 11:57:12 -03:00
|
|
|
mag_x = (float) rv.val[0];
|
|
|
|
mag_y = (float) rv.val[1];
|
|
|
|
mag_z = (float) rv.val[2];
|
2015-07-22 16:59:24 -03:00
|
|
|
|
|
|
|
if (is_zero(mag_x) && is_zero(mag_y) && is_zero(mag_z)) {
|
2015-07-31 11:57:12 -03:00
|
|
|
goto fail;
|
2015-07-22 16:59:24 -03:00
|
|
|
}
|
2015-07-31 01:55:16 -03:00
|
|
|
|
2015-09-03 08:26:54 -03:00
|
|
|
raw_field = Vector3f(mag_x, mag_y, mag_z);
|
2015-10-08 20:07:41 -03:00
|
|
|
|
|
|
|
_make_factory_sensitivity_adjustment(raw_field);
|
|
|
|
_make_adc_sensitivity_adjustment(raw_field);
|
2015-09-29 16:17:22 -03:00
|
|
|
raw_field *= AK8963_MILLIGAUSS_SCALE;
|
|
|
|
|
2015-07-31 01:55:16 -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, time_us, _compass_instance);
|
2015-07-22 16:59:24 -03:00
|
|
|
|
2015-07-31 01:55:16 -03:00
|
|
|
// 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, time_us, _compass_instance);
|
|
|
|
|
|
|
|
_mag_x_accum += raw_field.x;
|
|
|
|
_mag_y_accum += raw_field.y;
|
|
|
|
_mag_z_accum += raw_field.z;
|
2015-07-22 16:59:24 -03:00
|
|
|
_accum_count++;
|
|
|
|
if (_accum_count == 10) {
|
|
|
|
_mag_x_accum /= 2;
|
|
|
|
_mag_y_accum /= 2;
|
|
|
|
_mag_z_accum /= 2;
|
|
|
|
_accum_count = 5;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-11-19 23:09:17 -04:00
|
|
|
_last_update_timestamp = AP_HAL::micros();
|
2015-07-31 11:57:12 -03:00
|
|
|
fail:
|
2015-07-02 10:37:37 -03:00
|
|
|
_sem_give();
|
2015-07-31 11:57:12 -03:00
|
|
|
end:
|
|
|
|
return;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_check_id()
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
2015-07-02 10:37:37 -03:00
|
|
|
for (int i = 0; i < 5; i++) {
|
2015-07-09 11:06:59 -03:00
|
|
|
uint8_t deviceid = 0;
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus->register_read(AK8963_WIA, &deviceid, 0x01); /* Read AK8963's id */
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
if (deviceid == AK8963_Device_ID) {
|
|
|
|
return true;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
return false;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
bool AP_Compass_AK8963::_setup_mode() {
|
2015-07-21 11:30:01 -03:00
|
|
|
_bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);
|
2015-07-02 10:37:37 -03:00
|
|
|
return true;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_reset()
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus->register_write(AK8963_CNTL2, AK8963_RESET);
|
2015-07-02 10:37:37 -03:00
|
|
|
return true;
|
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_calibrate()
|
|
|
|
{
|
2015-07-09 11:06:59 -03:00
|
|
|
/* Enable FUSE-mode in order to be able to read calibration data */
|
2015-07-21 11:30:01 -03:00
|
|
|
_bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
uint8_t response[3];
|
2015-07-06 14:50:59 -03:00
|
|
|
_bus->register_read(AK8963_ASAX, response, 3);
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
for (int i = 0; i < 3; i++) {
|
|
|
|
float data = response[i];
|
|
|
|
_magnetometer_ASA[i] = ((data - 128) / 256 + 1);
|
|
|
|
error("%d: %lf\n", i, _magnetometer_ASA[i]);
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
return true;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_sem_take_blocking()
|
|
|
|
{
|
2015-07-06 14:50:59 -03:00
|
|
|
return _bus_sem->take(10);
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_sem_give()
|
|
|
|
{
|
2015-07-06 14:50:59 -03:00
|
|
|
return _bus_sem->give();
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
bool AP_Compass_AK8963::_sem_take_nonblocking()
|
|
|
|
{
|
|
|
|
static int _sem_failure_count = 0;
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-09 11:06:59 -03:00
|
|
|
if (_bus_sem->take_nonblocking()) {
|
|
|
|
_sem_failure_count = 0;
|
|
|
|
return true;
|
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-09 11:06:59 -03:00
|
|
|
if (!hal.scheduler->system_initializing() ) {
|
|
|
|
_sem_failure_count++;
|
|
|
|
if (_sem_failure_count > 100) {
|
2015-11-19 23:09:17 -04:00
|
|
|
AP_HAL::panic("PANIC: failed to take _bus->sem "
|
2015-07-22 16:11:20 -03:00
|
|
|
"100 times in a row, in "
|
|
|
|
"AP_Compass_AK8963");
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
2015-07-09 11:06:59 -03:00
|
|
|
|
|
|
|
return false;
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
void AP_Compass_AK8963::_dump_registers()
|
|
|
|
{
|
|
|
|
#if AK8963_DEBUG
|
|
|
|
error("MPU9250 registers\n");
|
|
|
|
static uint8_t regs[0x7e];
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
_bus_read(0x0, regs, 0x7e);
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-02 10:37:37 -03:00
|
|
|
for (uint8_t reg=0x00; reg<=0x7E; reg++) {
|
|
|
|
uint8_t v = regs[reg];
|
|
|
|
error(("%d:%02x "), (unsigned)reg, (unsigned)v);
|
|
|
|
if (reg % 16 == 0) {
|
|
|
|
error("\n");
|
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
2015-07-02 10:37:37 -03:00
|
|
|
error("\n");
|
2014-11-21 12:26:58 -04:00
|
|
|
#endif
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-07-10 01:05:21 -03:00
|
|
|
/* MPU9250 implementation of the AK8963 */
|
2015-09-28 11:21:31 -03:00
|
|
|
AP_AK8963_SerialBus_MPU9250::AP_AK8963_SerialBus_MPU9250(AP_InertialSensor &ins,
|
|
|
|
uint8_t addr,
|
|
|
|
uint8_t mpu9250_instance)
|
2015-07-02 10:37:37 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
// Only initialize members. Fails are handled by configure or while
|
|
|
|
// getting the semaphore
|
|
|
|
_bus = ins.get_auxiliary_bus(HAL_INS_MPU9250, mpu9250_instance);
|
|
|
|
if (!_bus)
|
2015-11-19 23:09:17 -04:00
|
|
|
AP_HAL::panic("Cannot get MPU9250 auxiliary bus");
|
2014-11-21 12:26:58 -04:00
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
_slave = _bus->request_next_slave(addr);
|
2015-07-02 10:37:37 -03:00
|
|
|
}
|
2015-07-06 14:50:59 -03:00
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
AP_AK8963_SerialBus_MPU9250::~AP_AK8963_SerialBus_MPU9250()
|
2015-07-02 10:37:37 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
/* After started it's owned by AuxiliaryBus */
|
|
|
|
if (!_started)
|
|
|
|
delete _slave;
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
void AP_AK8963_SerialBus_MPU9250::register_write(uint8_t reg, uint8_t value)
|
2014-11-21 12:26:58 -04:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
_slave->passthrough_write(reg, value);
|
2014-11-21 12:26:58 -04:00
|
|
|
}
|
2015-07-06 14:50:59 -03:00
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
void AP_AK8963_SerialBus_MPU9250::register_read(uint8_t reg, uint8_t *value, uint8_t count)
|
2015-07-06 14:50:59 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
_slave->passthrough_read(reg, value, count);
|
2015-07-06 14:50:59 -03:00
|
|
|
}
|
|
|
|
|
2015-07-21 03:49:42 -03:00
|
|
|
void AP_AK8963_SerialBus_MPU9250::read_raw(struct raw_value *rv)
|
2015-07-06 14:50:59 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
if (_started) {
|
|
|
|
_slave->read((uint8_t*)rv);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
_slave->passthrough_read(0x03, (uint8_t*)rv, sizeof(*rv));
|
2015-07-06 14:50:59 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::Semaphore * AP_AK8963_SerialBus_MPU9250::get_semaphore()
|
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
return _bus ? _bus->get_semaphore() : nullptr;
|
2015-07-06 14:50:59 -03:00
|
|
|
}
|
|
|
|
|
2015-07-22 16:11:20 -03:00
|
|
|
bool AP_AK8963_SerialBus_MPU9250::start_measurements()
|
2015-07-06 14:50:59 -03:00
|
|
|
{
|
2015-09-28 11:21:31 -03:00
|
|
|
if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(struct raw_value)) < 0)
|
|
|
|
return false;
|
2015-07-22 18:36:46 -03:00
|
|
|
|
2015-09-28 11:21:31 -03:00
|
|
|
_started = true;
|
2015-07-06 14:50:59 -03:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
2015-07-10 01:05:21 -03:00
|
|
|
|
|
|
|
uint32_t AP_AK8963_SerialBus_MPU9250::get_dev_id()
|
|
|
|
{
|
|
|
|
return AP_COMPASS_TYPE_AK8963_MPU9250;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* I2C implementation of the AK8963 */
|
|
|
|
AP_AK8963_SerialBus_I2C::AP_AK8963_SerialBus_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr) :
|
|
|
|
_i2c(i2c),
|
|
|
|
_addr(addr)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2015-09-14 13:19:34 -03:00
|
|
|
void AP_AK8963_SerialBus_I2C::register_write(uint8_t reg, uint8_t value)
|
2015-07-10 01:05:21 -03:00
|
|
|
{
|
2015-09-14 13:19:34 -03:00
|
|
|
_i2c->writeRegister(_addr, reg, value);
|
2015-07-10 01:05:21 -03:00
|
|
|
}
|
|
|
|
|
2015-09-14 13:19:34 -03:00
|
|
|
void AP_AK8963_SerialBus_I2C::register_read(uint8_t reg, uint8_t *value, uint8_t count)
|
2015-07-10 01:05:21 -03:00
|
|
|
{
|
2015-09-14 13:19:34 -03:00
|
|
|
_i2c->readRegisters(_addr, reg, count, value);
|
2015-07-10 01:05:21 -03:00
|
|
|
}
|
|
|
|
|
2015-07-21 03:49:42 -03:00
|
|
|
void AP_AK8963_SerialBus_I2C::read_raw(struct raw_value *rv)
|
2015-07-10 01:05:21 -03:00
|
|
|
{
|
2015-07-22 18:46:42 -03:00
|
|
|
_i2c->readRegisters(_addr, AK8963_HXL, sizeof(*rv), (uint8_t *) rv);
|
2015-07-10 01:05:21 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::Semaphore * AP_AK8963_SerialBus_I2C::get_semaphore()
|
|
|
|
{
|
|
|
|
return _i2c->get_semaphore();
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t AP_AK8963_SerialBus_I2C::get_dev_id()
|
|
|
|
{
|
|
|
|
return AP_COMPASS_TYPE_AK8963_I2C;
|
|
|
|
}
|
|
|
|
|
2015-07-08 22:57:27 -03:00
|
|
|
#endif // CONFIG_HAL_BOARD
|