2013-01-04 01:10:51 -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/>.
|
|
|
|
*/
|
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
/*
|
|
|
|
* AP_Compass_PX4.cpp - Arduino Library for PX4 magnetometer
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include "AP_Compass_PX4.h"
|
|
|
|
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
|
|
|
#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 //////////////////////////////////////////////////////////////
|
|
|
|
|
|
|
|
bool AP_Compass_PX4::init(void)
|
|
|
|
{
|
|
|
|
_mag_fd = open(MAG_DEVICE_PATH, O_RDONLY);
|
|
|
|
if (_mag_fd < 0) {
|
2013-09-08 19:25:35 -03:00
|
|
|
hal.console->printf("Unable to open " MAG_DEVICE_PATH "\n");
|
2013-01-04 01:10:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2013-09-09 04:26:14 -03:00
|
|
|
/* set the driver to poll at 100Hz */
|
|
|
|
if (0 != ioctl(_mag_fd, SENSORIOCSPOLLRATE, 100)) {
|
2013-09-08 19:25:35 -03:00
|
|
|
hal.console->printf("Failed to setup compass poll rate\n");
|
|
|
|
return false;
|
|
|
|
}
|
2013-01-04 01:10:51 -04:00
|
|
|
|
2013-08-28 06:18:05 -03:00
|
|
|
// average over up to 20 samples
|
2013-09-08 19:25:35 -03:00
|
|
|
if (ioctl(_mag_fd, SENSORIOCSQUEUEDEPTH, 20) != 0) {
|
|
|
|
hal.console->printf("Failed to setup compass queue\n");
|
|
|
|
return false;
|
|
|
|
}
|
2013-01-04 05:12:03 -04:00
|
|
|
|
2013-08-30 01:02:09 -03:00
|
|
|
// remember if the compass is external
|
|
|
|
_is_external = (ioctl(_mag_fd, MAGIOCGEXTERNAL, 0) > 0);
|
2013-09-08 19:25:35 -03:00
|
|
|
if (_is_external) {
|
|
|
|
hal.console->printf("Using external compass\n");
|
|
|
|
}
|
2013-08-30 01:02:09 -03:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
healthy = false;
|
|
|
|
_count = 0;
|
|
|
|
_sum.zero();
|
|
|
|
|
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-09-08 19:25:35 -03:00
|
|
|
if (_count == 0) {
|
|
|
|
hal.console->printf("Failed initial compass accumulate\n");
|
|
|
|
}
|
2013-01-04 01:10:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_Compass_PX4::read(void)
|
|
|
|
{
|
2013-09-08 19:25:35 -03:00
|
|
|
bool was_healthy = healthy;
|
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
|
|
|
|
|
|
|
// consider the compass healthy if we got a reading in the last 0.2s
|
|
|
|
healthy = (hrt_absolute_time() - _last_timestamp < 200000);
|
|
|
|
if (!healthy || _count == 0) {
|
2013-09-08 19:25:35 -03:00
|
|
|
if (was_healthy) {
|
|
|
|
hal.console->printf("Compass unhealthy deltat=%u _count=%u\n",
|
|
|
|
(unsigned)(hrt_absolute_time() - _last_timestamp),
|
|
|
|
(unsigned)_count);
|
|
|
|
}
|
2013-04-30 19:54:36 -03:00
|
|
|
return healthy;
|
2013-01-04 01:10:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
_sum /= _count;
|
|
|
|
_sum *= 1000;
|
2013-05-01 23:27:35 -03:00
|
|
|
|
|
|
|
// apply default board orientation for this compass type. This is
|
|
|
|
// a noop on most boards
|
2013-05-02 00:00:52 -03:00
|
|
|
_sum.rotate(MAG_BOARD_ORIENTATION);
|
2013-05-01 23:27:35 -03:00
|
|
|
|
2013-08-30 01:02:09 -03:00
|
|
|
// override any user setting of COMPASS_EXTERNAL
|
|
|
|
_external.set(_is_external);
|
|
|
|
|
2013-09-07 03:49:51 -03:00
|
|
|
if (_external) {
|
|
|
|
// add user selectable orientation
|
|
|
|
_sum.rotate((enum Rotation)_orientation.get());
|
|
|
|
} else {
|
2013-08-30 01:02:09 -03:00
|
|
|
// add in board orientation from AHRS
|
|
|
|
_sum.rotate(_board_orientation);
|
|
|
|
}
|
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
_sum += _offset.get();
|
|
|
|
|
2013-03-03 10:02:12 -04:00
|
|
|
// apply motor compensation
|
2013-04-30 19:54:36 -03:00
|
|
|
if (_motor_comp_type != AP_COMPASS_MOT_COMP_DISABLED && _thr_or_curr != 0.0f) {
|
2013-03-03 10:02:12 -04:00
|
|
|
_motor_offset = _motor_compensation.get() * _thr_or_curr;
|
2013-02-27 03:57:04 -04:00
|
|
|
_sum += _motor_offset;
|
2013-04-30 19:54:36 -03:00
|
|
|
} else {
|
2013-02-27 03:57:04 -04:00
|
|
|
_motor_offset.x = 0;
|
|
|
|
_motor_offset.y = 0;
|
|
|
|
_motor_offset.z = 0;
|
|
|
|
}
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
mag_x = _sum.x;
|
|
|
|
mag_y = _sum.y;
|
|
|
|
mag_z = _sum.z;
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
_sum.zero();
|
|
|
|
_count = 0;
|
|
|
|
|
2013-01-22 05:08:33 -04:00
|
|
|
last_update = _last_timestamp;
|
2013-04-30 19:54:36 -03:00
|
|
|
|
2013-01-04 01:10:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
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;
|
2013-01-22 05:08:33 -04:00
|
|
|
while (::read(_mag_fd, &mag_report, sizeof(mag_report)) == sizeof(mag_report) &&
|
|
|
|
mag_report.timestamp != _last_timestamp) {
|
2013-01-04 05:12:03 -04:00
|
|
|
_sum += Vector3f(mag_report.x, mag_report.y, mag_report.z);
|
|
|
|
_count++;
|
2013-01-22 05:08:33 -04:00
|
|
|
_last_timestamp = mag_report.timestamp;
|
2013-01-04 05:12:03 -04:00
|
|
|
}
|
2013-01-04 01:10:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|