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/>.
|
|
|
|
*/
|
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
/*
|
|
|
|
* AP_Compass_PX4.cpp - Arduino Library for PX4 magnetometer
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-04 01:10:51 -04:00
|
|
|
|
2015-02-23 19:17:44 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
2013-01-04 01:10:51 -04:00
|
|
|
#include "AP_Compass_PX4.h"
|
|
|
|
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
2014-07-07 09:30:23 -03:00
|
|
|
#include <drivers/drv_device.h>
|
2013-01-04 01:10:51 -04:00
|
|
|
#include <drivers/drv_mag.h>
|
2013-04-30 19:54:36 -03:00
|
|
|
#include <drivers/drv_hrt.h>
|
2013-01-04 01:10:51 -04:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <errno.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
// Public Methods //////////////////////////////////////////////////////////////
|
|
|
|
|
2014-11-15 21:58:23 -04:00
|
|
|
// constructor
|
|
|
|
AP_Compass_PX4::AP_Compass_PX4(Compass &compass):
|
2015-03-13 05:16:50 -03:00
|
|
|
AP_Compass_Backend(compass),
|
|
|
|
_num_sensors(0)
|
|
|
|
{
|
|
|
|
}
|
2014-11-15 21:58:23 -04:00
|
|
|
|
|
|
|
// detect the sensor
|
|
|
|
AP_Compass_Backend *AP_Compass_PX4::detect(Compass &compass)
|
|
|
|
{
|
|
|
|
AP_Compass_PX4 *sensor = new AP_Compass_PX4(compass);
|
2016-10-30 02:24:21 -03:00
|
|
|
if (sensor == nullptr) {
|
|
|
|
return nullptr;
|
2014-11-15 21:58:23 -04:00
|
|
|
}
|
|
|
|
if (!sensor->init()) {
|
|
|
|
delete sensor;
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2014-11-15 21:58:23 -04:00
|
|
|
}
|
|
|
|
return sensor;
|
|
|
|
}
|
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
bool AP_Compass_PX4::init(void)
|
|
|
|
{
|
2015-02-13 04:19:47 -04:00
|
|
|
_mag_fd[0] = open(MAG_BASE_DEVICE_PATH"0", O_RDONLY);
|
|
|
|
_mag_fd[1] = open(MAG_BASE_DEVICE_PATH"1", O_RDONLY);
|
|
|
|
_mag_fd[2] = open(MAG_BASE_DEVICE_PATH"2", O_RDONLY);
|
2014-07-03 23:07:47 -03:00
|
|
|
|
2015-02-23 19:17:44 -04:00
|
|
|
_num_sensors = 0;
|
2014-07-03 23:07:47 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
if (_mag_fd[i] >= 0) {
|
2015-02-23 19:17:44 -04:00
|
|
|
_num_sensors = i+1;
|
2014-07-03 23:07:47 -03:00
|
|
|
}
|
|
|
|
}
|
2015-02-23 19:17:44 -04:00
|
|
|
if (_num_sensors == 0) {
|
2015-02-13 04:19:47 -04:00
|
|
|
hal.console->printf("Unable to open " MAG_BASE_DEVICE_PATH"0" "\n");
|
2013-01-04 01:10:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-02-23 19:17:44 -04:00
|
|
|
for (uint8_t i=0; i<_num_sensors; i++) {
|
2015-03-13 06:46:32 -03:00
|
|
|
_instance[i] = register_compass();
|
|
|
|
|
2014-07-07 09:30:23 -03:00
|
|
|
// get device id
|
2015-02-23 19:17:44 -04:00
|
|
|
set_dev_id(_instance[i], ioctl(_mag_fd[i], DEVIOCGDEVICEID, 0));
|
|
|
|
|
2013-12-09 01:05:57 -04:00
|
|
|
// average over up to 20 samples
|
|
|
|
if (ioctl(_mag_fd[i], SENSORIOCSQUEUEDEPTH, 20) != 0) {
|
|
|
|
hal.console->printf("Failed to setup compass queue\n");
|
|
|
|
return false;
|
|
|
|
}
|
2013-01-04 05:12:03 -04:00
|
|
|
|
2013-12-09 01:05:57 -04:00
|
|
|
// remember if the compass is external
|
2015-02-23 19:17:44 -04:00
|
|
|
set_external(_instance[i], ioctl(_mag_fd[i], MAGIOCGEXTERNAL, 0) > 0);
|
2015-03-13 05:16:50 -03:00
|
|
|
_count[i] = 0;
|
2013-12-09 01:05:57 -04:00
|
|
|
_sum[i].zero();
|
2015-09-09 01:52:14 -03:00
|
|
|
|
2013-09-08 19:25:35 -03:00
|
|
|
}
|
2013-08-30 01:02:09 -03:00
|
|
|
|
2013-08-28 06:18:05 -03:00
|
|
|
// give the driver a chance to run, and gather one sample
|
2013-04-30 19:54:36 -03:00
|
|
|
hal.scheduler->delay(40);
|
2013-08-28 06:18:05 -03:00
|
|
|
accumulate();
|
2013-12-09 01:05:57 -04:00
|
|
|
if (_count[0] == 0) {
|
2013-09-08 19:25:35 -03:00
|
|
|
hal.console->printf("Failed initial compass accumulate\n");
|
|
|
|
}
|
2014-11-15 21:58:23 -04:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2015-02-23 19:17:44 -04:00
|
|
|
void AP_Compass_PX4::read(void)
|
2013-01-04 01:10:51 -04:00
|
|
|
{
|
2013-04-30 19:54:36 -03:00
|
|
|
// try to accumulate one more sample, so we have the latest data
|
2013-08-28 06:18:05 -03:00
|
|
|
accumulate();
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2015-02-23 19:17:44 -04:00
|
|
|
for (uint8_t i=0; i<_num_sensors; i++) {
|
2015-03-18 19:17:25 -03:00
|
|
|
uint8_t frontend_instance = _instance[i];
|
2014-03-20 02:27:32 -03:00
|
|
|
// avoid division by zero if we haven't received any mag reports
|
|
|
|
if (_count[i] == 0) continue;
|
|
|
|
|
2013-12-09 01:05:57 -04:00
|
|
|
_sum[i] /= _count[i];
|
2013-05-01 23:27:35 -03:00
|
|
|
|
2015-03-18 19:17:25 -03:00
|
|
|
publish_filtered_field(_sum[i], frontend_instance);
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2013-12-09 01:05:57 -04:00
|
|
|
_sum[i].zero();
|
|
|
|
_count[i] = 0;
|
|
|
|
}
|
2013-01-04 01:10:51 -04:00
|
|
|
}
|
|
|
|
|
2013-08-28 06:18:05 -03:00
|
|
|
void AP_Compass_PX4::accumulate(void)
|
2013-01-04 01:10:51 -04:00
|
|
|
{
|
2013-01-04 05:12:03 -04:00
|
|
|
struct mag_report mag_report;
|
2015-02-23 19:17:44 -04:00
|
|
|
for (uint8_t i=0; i<_num_sensors; i++) {
|
2015-03-18 19:17:25 -03:00
|
|
|
uint8_t frontend_instance = _instance[i];
|
2013-12-09 01:05:57 -04:00
|
|
|
while (::read(_mag_fd[i], &mag_report, sizeof(mag_report)) == sizeof(mag_report) &&
|
|
|
|
mag_report.timestamp != _last_timestamp[i]) {
|
2015-03-18 19:17:25 -03:00
|
|
|
|
|
|
|
uint32_t time_us = (uint32_t)mag_report.timestamp;
|
|
|
|
// get raw_field - sensor frame, uncorrected
|
|
|
|
Vector3f raw_field = Vector3f(mag_report.x, mag_report.y, mag_report.z)*1.0e3f;
|
|
|
|
|
|
|
|
// rotate raw_field from sensor frame to body frame
|
|
|
|
rotate_field(raw_field, frontend_instance);
|
|
|
|
|
|
|
|
// publish raw_field (uncorrected point sample) for calibration use
|
|
|
|
publish_raw_field(raw_field, time_us, frontend_instance);
|
|
|
|
|
|
|
|
// correct raw_field for known errors
|
|
|
|
correct_field(raw_field, frontend_instance);
|
|
|
|
|
|
|
|
// accumulate into averaging filter
|
|
|
|
_sum[i] += raw_field;
|
2013-12-09 01:05:57 -04:00
|
|
|
_count[i]++;
|
2015-03-18 19:17:25 -03:00
|
|
|
|
2013-12-09 01:05:57 -04:00
|
|
|
_last_timestamp[i] = mag_report.timestamp;
|
|
|
|
}
|
2013-01-04 05:12:03 -04:00
|
|
|
}
|
2013-01-04 01:10:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|