ardupilot/libraries/AP_Compass/AP_Compass_HIL.cpp

117 lines
3.2 KiB
C++
Raw Normal View History

2013-05-02 08:31:17 -03: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/>.
*/
/*
* AP_Compass_HIL.cpp - Arduino Library for HIL model of HMC5843 I2C Magnetometer
* Code by James Goppert. DIYDrones.com
*
*/
2012-10-11 17:48:39 -03:00
#include <AP_HAL.h>
#include "AP_Compass_HIL.h"
2012-10-11 17:48:39 -03:00
extern const AP_HAL::HAL& hal;
// constructor
AP_Compass_HIL::AP_Compass_HIL() : Compass()
{
2013-05-02 08:31:17 -03:00
product_id = AP_COMPASS_TYPE_HIL;
_setup_earth_field();
}
// setup _Bearth
void AP_Compass_HIL::_setup_earth_field(void)
{
2013-05-02 08:31:17 -03:00
// assume a earth field strength of 400
_Bearth(400, 0, 0);
// rotate _Bearth for inclination and declination. -66 degrees
// is the inclination in Canberra, Australia
Matrix3f R;
R.from_euler(0, ToRad(66), _declination.get());
_Bearth = R * _Bearth;
}
// Public Methods //////////////////////////////////////////////////////////////
bool AP_Compass_HIL::read()
{
// get offsets
Vector3f ofs = _offset.get();
// apply motor compensation
if(_motor_comp_type != AP_COMPASS_MOT_COMP_DISABLED && _thr_or_curr != 0.0f) {
_motor_offset = _motor_compensation.get() * _thr_or_curr;
}else{
_motor_offset.x = 0;
_motor_offset.y = 0;
_motor_offset.z = 0;
}
// return last values provided by setHIL function
mag_x = _hil_mag.x + ofs.x + _motor_offset.x;
mag_y = _hil_mag.y + ofs.y + _motor_offset.y;
mag_z = _hil_mag.z + ofs.z + _motor_offset.z;
// values set by setHIL function
2012-10-11 17:48:39 -03:00
last_update = hal.scheduler->micros(); // record time of update
return true;
}
#define MAG_OFS_X 5.0
#define MAG_OFS_Y 13.0
#define MAG_OFS_Z -18.0
// Update raw magnetometer values from HIL data
//
void AP_Compass_HIL::setHIL(float roll, float pitch, float yaw)
{
2013-05-02 08:31:17 -03:00
Matrix3f R;
2013-05-02 08:31:17 -03:00
// create a rotation matrix for the given attitude
R.from_euler(roll, pitch, yaw);
2013-05-02 08:31:17 -03:00
if (_last_declination != _declination.get()) {
_setup_earth_field();
_last_declination = _declination.get();
}
2013-05-02 08:31:17 -03:00
// convert the earth frame magnetic vector to body frame, and
// apply the offsets
_hil_mag = R.mul_transpose(_Bearth);
_hil_mag -= Vector3f(MAG_OFS_X, MAG_OFS_Y, MAG_OFS_Z);
2013-05-02 08:31:17 -03:00
// apply default board orientation for this compass type. This is
// a noop on most boards
_hil_mag.rotate(MAG_BOARD_ORIENTATION);
2013-05-02 08:31:17 -03:00
// add user selectable orientation
_hil_mag.rotate((enum Rotation)_orientation.get());
if (!_external) {
// and add in AHRS_ORIENTATION setting if not an external compass
_hil_mag.rotate(_board_orientation);
}
2013-05-02 08:31:17 -03:00
healthy = true;
}
void AP_Compass_HIL::accumulate(void)
{
2013-05-02 08:31:17 -03:00
// nothing to do
}