2012-12-12 17:42:14 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
#ifndef __AP_AHRS_H__
|
|
|
|
#define __AP_AHRS_H__
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2012-03-19 03:34:12 -03:00
|
|
|
/*
|
2012-08-21 23:19:51 -03:00
|
|
|
* AHRS (Attitude Heading Reference System) interface for ArduPilot
|
|
|
|
*
|
|
|
|
*/
|
2012-03-19 03:34:12 -03:00
|
|
|
|
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <inttypes.h>
|
|
|
|
#include <AP_Compass.h>
|
2012-08-10 19:57:32 -03:00
|
|
|
#include <AP_Airspeed.h>
|
2012-03-19 03:34:12 -03:00
|
|
|
#include <AP_GPS.h>
|
2012-11-05 00:29:00 -04:00
|
|
|
#include <AP_InertialSensor.h>
|
2012-06-19 01:47:09 -03:00
|
|
|
#include <AP_Baro.h>
|
2012-08-20 20:22:44 -03:00
|
|
|
#include <AP_Param.h>
|
2012-03-19 03:34:12 -03:00
|
|
|
|
2013-02-19 05:50:57 -04:00
|
|
|
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
|
|
|
|
2014-04-21 04:10:27 -03:00
|
|
|
enum AHRS_VehicleClass {
|
|
|
|
AHRS_VEHICLE_UNKNOWN,
|
|
|
|
AHRS_VEHICLE_GROUND,
|
|
|
|
AHRS_VEHICLE_COPTER,
|
|
|
|
AHRS_VEHICLE_FIXED_WING,
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2012-03-19 03:34:12 -03:00
|
|
|
class AP_AHRS
|
|
|
|
{
|
|
|
|
public:
|
2012-08-21 23:19:51 -03:00
|
|
|
// Constructor
|
2014-03-30 08:00:25 -03:00
|
|
|
AP_AHRS(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps) :
|
2014-07-14 11:17:43 -03:00
|
|
|
roll(0.0f),
|
|
|
|
pitch(0.0f),
|
|
|
|
yaw(0.0f),
|
|
|
|
roll_sensor(0),
|
|
|
|
pitch_sensor(0),
|
|
|
|
yaw_sensor(0),
|
2014-04-21 04:10:27 -03:00
|
|
|
_vehicle_class(AHRS_VEHICLE_UNKNOWN),
|
2013-11-27 22:16:51 -04:00
|
|
|
_compass(NULL),
|
2014-07-14 11:17:43 -03:00
|
|
|
_airspeed(NULL),
|
|
|
|
_compass_last_update(0),
|
2012-11-05 00:29:00 -04:00
|
|
|
_ins(ins),
|
2014-02-15 04:38:43 -04:00
|
|
|
_baro(baro),
|
|
|
|
_gps(gps),
|
2014-02-08 02:52:03 -04:00
|
|
|
_cos_roll(1.0f),
|
|
|
|
_cos_pitch(1.0f),
|
|
|
|
_cos_yaw(1.0f),
|
|
|
|
_sin_roll(0.0f),
|
|
|
|
_sin_pitch(0.0f),
|
2014-02-26 18:41:28 -04:00
|
|
|
_sin_yaw(0.0f),
|
|
|
|
_active_accel_instance(0)
|
2012-08-21 23:19:51 -03:00
|
|
|
{
|
2012-12-12 17:42:14 -04:00
|
|
|
// load default values from var_info table
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// base the ki values by the sensors maximum drift
|
|
|
|
// rate. The APM2 has gyros which are much less drift
|
|
|
|
// prone than the APM1, so we should have a lower ki,
|
|
|
|
// which will make us less prone to increasing omegaI
|
|
|
|
// incorrectly due to sensor noise
|
2013-11-03 23:34:32 -04:00
|
|
|
_gyro_drift_limit = ins.get_gyro_drift_rate();
|
2013-05-06 01:31:49 -03:00
|
|
|
|
|
|
|
// enable centrifugal correction by default
|
|
|
|
_flags.correct_centrifugal = true;
|
2014-01-02 07:06:10 -04:00
|
|
|
|
2014-02-18 19:52:24 -04:00
|
|
|
// start off with armed flag true
|
|
|
|
_flags.armed = true;
|
|
|
|
|
2014-01-02 07:06:10 -04:00
|
|
|
// initialise _home
|
|
|
|
_home.options = 0;
|
|
|
|
_home.alt = 0;
|
|
|
|
_home.lng = 0;
|
|
|
|
_home.lat = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
|
2014-07-15 01:29:34 -03:00
|
|
|
// empty virtual destructor
|
|
|
|
virtual ~AP_AHRS() {}
|
|
|
|
|
2013-01-13 01:03:35 -04:00
|
|
|
// init sets up INS board orientation
|
2012-11-14 12:10:15 -04:00
|
|
|
virtual void init() {
|
2013-06-03 03:52:28 -03:00
|
|
|
set_orientation();
|
2012-08-21 23:19:51 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Accessors
|
2012-11-14 12:10:15 -04:00
|
|
|
void set_fly_forward(bool b) {
|
2013-05-06 01:31:49 -03:00
|
|
|
_flags.fly_forward = b;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2013-05-23 22:21:23 -03:00
|
|
|
|
2014-02-27 02:39:49 -04:00
|
|
|
bool get_fly_forward(void) const {
|
|
|
|
return _flags.fly_forward;
|
|
|
|
}
|
|
|
|
|
2014-04-21 04:10:27 -03:00
|
|
|
AHRS_VehicleClass get_vehicle_class(void) const {
|
|
|
|
return _vehicle_class;
|
|
|
|
}
|
|
|
|
|
|
|
|
void set_vehicle_class(AHRS_VehicleClass vclass) {
|
|
|
|
_vehicle_class = vclass;
|
|
|
|
}
|
|
|
|
|
2013-05-23 22:21:23 -03:00
|
|
|
void set_wind_estimation(bool b) {
|
|
|
|
_flags.wind_estimation = b;
|
|
|
|
}
|
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
void set_compass(Compass *compass) {
|
2012-08-21 23:19:51 -03:00
|
|
|
_compass = compass;
|
2013-06-03 03:52:28 -03:00
|
|
|
set_orientation();
|
|
|
|
}
|
|
|
|
|
2013-11-27 22:16:51 -04:00
|
|
|
const Compass* get_compass() const {
|
|
|
|
return _compass;
|
|
|
|
}
|
|
|
|
|
2013-06-03 03:52:28 -03:00
|
|
|
// allow for runtime change of orientation
|
|
|
|
// this makes initial config easier
|
|
|
|
void set_orientation() {
|
2013-11-03 23:34:32 -04:00
|
|
|
_ins.set_board_orientation((enum Rotation)_board_orientation.get());
|
2013-01-16 21:27:59 -04:00
|
|
|
if (_compass != NULL) {
|
|
|
|
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
|
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2013-06-03 03:52:28 -03:00
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
void set_airspeed(AP_Airspeed *airspeed) {
|
2012-08-21 23:19:51 -03:00
|
|
|
_airspeed = airspeed;
|
|
|
|
}
|
|
|
|
|
2013-12-30 06:24:18 -04:00
|
|
|
const AP_Airspeed *get_airspeed(void) const {
|
|
|
|
return _airspeed;
|
|
|
|
}
|
|
|
|
|
2014-03-30 08:00:25 -03:00
|
|
|
const AP_GPS &get_gps() const {
|
2013-11-27 22:16:51 -04:00
|
|
|
return _gps;
|
|
|
|
}
|
|
|
|
|
2013-11-03 23:34:32 -04:00
|
|
|
const AP_InertialSensor &get_ins() const {
|
2012-11-05 00:29:00 -04:00
|
|
|
return _ins;
|
2012-08-21 23:14:39 -03:00
|
|
|
}
|
|
|
|
|
2014-01-02 02:06:30 -04:00
|
|
|
const AP_Baro &get_baro() const {
|
|
|
|
return _baro;
|
|
|
|
}
|
|
|
|
|
2012-12-12 03:22:56 -04:00
|
|
|
// accelerometer values in the earth frame in m/s/s
|
2014-02-27 01:28:37 -04:00
|
|
|
const Vector3f &get_accel_ef(void) const { return _accel_ef[_ins.get_primary_accel()]; }
|
2012-12-12 03:22:56 -04:00
|
|
|
|
2014-10-06 17:15:19 -03:00
|
|
|
// get yaw rate in earth frame in radians/sec
|
|
|
|
float get_yaw_rate_earth(void) const { return get_gyro() * get_dcm_matrix().c; }
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Methods
|
|
|
|
virtual void update(void) = 0;
|
|
|
|
|
|
|
|
// Euler angles (radians)
|
|
|
|
float roll;
|
|
|
|
float pitch;
|
|
|
|
float yaw;
|
|
|
|
|
|
|
|
// integer Euler angles (Degrees * 100)
|
|
|
|
int32_t roll_sensor;
|
|
|
|
int32_t pitch_sensor;
|
|
|
|
int32_t yaw_sensor;
|
|
|
|
|
|
|
|
// return a smoothed and corrected gyro vector
|
2014-07-13 08:56:39 -03:00
|
|
|
virtual const Vector3f &get_gyro(void) const = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
|
|
|
// return the current estimate of the gyro drift
|
2013-04-21 09:27:04 -03:00
|
|
|
virtual const Vector3f &get_gyro_drift(void) const = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
|
|
|
// reset the current attitude, used on new IMU calibration
|
|
|
|
virtual void reset(bool recover_eulers=false) = 0;
|
|
|
|
|
2013-11-22 21:37:23 -04:00
|
|
|
// reset the current attitude, used on new IMU calibration
|
|
|
|
virtual void reset_attitude(const float &roll, const float &pitch, const float &yaw) = 0;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// return the average size of the roll/pitch error estimate
|
|
|
|
// since last call
|
|
|
|
virtual float get_error_rp(void) = 0;
|
|
|
|
|
|
|
|
// return the average size of the yaw error estimate
|
|
|
|
// since last call
|
|
|
|
virtual float get_error_yaw(void) = 0;
|
|
|
|
|
|
|
|
// return a DCM rotation matrix representing our current
|
|
|
|
// attitude
|
2013-04-21 09:27:04 -03:00
|
|
|
virtual const Matrix3f &get_dcm_matrix(void) const = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
2014-01-02 07:06:10 -04:00
|
|
|
// get our current position estimate. Return true if a position is available,
|
|
|
|
// otherwise false. This call fills in lat, lng and alt
|
|
|
|
virtual bool get_position(struct Location &loc) = 0;
|
2013-08-12 00:28:23 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// return a wind estimation vector, in m/s
|
2014-01-02 07:06:10 -04:00
|
|
|
virtual Vector3f wind_estimate(void) = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
2012-08-24 08:22:58 -03:00
|
|
|
// return an airspeed estimate if available. return true
|
|
|
|
// if we have an estimate
|
2013-12-29 03:36:40 -04:00
|
|
|
virtual bool airspeed_estimate(float *airspeed_ret) const;
|
2012-08-24 08:22:58 -03:00
|
|
|
|
2013-07-19 22:11:57 -03:00
|
|
|
// return a true airspeed estimate (navigation airspeed) if
|
|
|
|
// available. return true if we have an estimate
|
2013-12-29 03:36:40 -04:00
|
|
|
bool airspeed_estimate_true(float *airspeed_ret) const {
|
2013-07-19 22:11:57 -03:00
|
|
|
if (!airspeed_estimate(airspeed_ret)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
*airspeed_ret *= get_EAS2TAS();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get apparent to true airspeed ratio
|
|
|
|
float get_EAS2TAS(void) const {
|
|
|
|
if (_airspeed) {
|
|
|
|
return _airspeed->get_EAS2TAS();
|
|
|
|
}
|
|
|
|
return 1.0f;
|
|
|
|
}
|
|
|
|
|
2013-06-26 07:46:26 -03:00
|
|
|
// return true if airspeed comes from an airspeed sensor, as
|
|
|
|
// opposed to an IMU estimate
|
|
|
|
bool airspeed_sensor_enabled(void) const {
|
|
|
|
return _airspeed != NULL && _airspeed->use();
|
|
|
|
}
|
|
|
|
|
2013-03-29 03:23:22 -03:00
|
|
|
// return a ground vector estimate in meters/second, in North/East order
|
2014-01-01 23:25:41 -04:00
|
|
|
virtual Vector2f groundspeed_vector(void);
|
2013-03-29 03:23:22 -03:00
|
|
|
|
2014-01-03 20:15:34 -04:00
|
|
|
// return a ground velocity in meters/second, North/East/Down
|
|
|
|
// order. This will only be accurate if have_inertial_nav() is
|
|
|
|
// true
|
2014-02-08 04:11:12 -04:00
|
|
|
virtual bool get_velocity_NED(Vector3f &vec) const { return false; }
|
2014-01-03 20:15:34 -04:00
|
|
|
|
|
|
|
// return a position relative to home in meters, North/East/Down
|
|
|
|
// order. This will only be accurate if have_inertial_nav() is
|
|
|
|
// true
|
2014-02-08 04:11:12 -04:00
|
|
|
virtual bool get_relative_position_NED(Vector3f &vec) const { return false; }
|
2014-01-03 20:15:34 -04:00
|
|
|
|
2013-09-08 21:17:45 -03:00
|
|
|
// return ground speed estimate in meters/second. Used by ground vehicles.
|
|
|
|
float groundspeed(void) const {
|
2014-03-30 08:00:25 -03:00
|
|
|
if (_gps.status() <= AP_GPS::NO_FIX) {
|
2013-09-08 21:17:45 -03:00
|
|
|
return 0.0f;
|
|
|
|
}
|
2014-03-30 08:00:25 -03:00
|
|
|
return _gps.ground_speed();
|
2013-09-08 21:17:45 -03:00
|
|
|
}
|
|
|
|
|
2013-03-28 23:48:25 -03:00
|
|
|
// return true if we will use compass for yaw
|
2013-10-21 23:06:27 -03:00
|
|
|
virtual bool use_compass(void) { return _compass && _compass->use_for_yaw(); }
|
2013-03-28 23:48:25 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// return true if yaw has been initialised
|
2013-04-21 09:27:04 -03:00
|
|
|
bool yaw_initialised(void) const {
|
2013-05-06 01:31:49 -03:00
|
|
|
return _flags.have_initial_yaw;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// set the fast gains flag
|
|
|
|
void set_fast_gains(bool setting) {
|
2013-05-06 01:31:49 -03:00
|
|
|
_flags.fast_ground_gains = setting;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set the correct centrifugal flag
|
|
|
|
// allows arducopter to disable corrections when disarmed
|
2014-02-18 19:28:14 -04:00
|
|
|
void set_correct_centrifugal(bool setting) {
|
2013-05-06 01:31:49 -03:00
|
|
|
_flags.correct_centrifugal = setting;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
|
2014-02-18 19:28:14 -04:00
|
|
|
// get the correct centrifugal flag
|
|
|
|
bool get_correct_centrifugal(void) const {
|
|
|
|
return _flags.correct_centrifugal;
|
|
|
|
}
|
|
|
|
|
2014-02-18 19:52:24 -04:00
|
|
|
// set the armed flag
|
|
|
|
// allows EKF enter static mode when disarmed
|
|
|
|
void set_armed(bool setting) {
|
|
|
|
_flags.armed = setting;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get the armed flag
|
|
|
|
bool get_armed(void) const {
|
|
|
|
return _flags.armed;
|
|
|
|
}
|
|
|
|
|
2013-02-19 05:50:57 -04:00
|
|
|
// get trim
|
2013-04-21 09:27:04 -03:00
|
|
|
const Vector3f &get_trim() const { return _trim.get(); }
|
2012-11-05 00:29:00 -04:00
|
|
|
|
2013-02-19 05:50:57 -04:00
|
|
|
// set trim
|
|
|
|
virtual void set_trim(Vector3f new_trim);
|
2012-11-05 00:29:00 -04:00
|
|
|
|
|
|
|
// add_trim - adjust the roll and pitch trim up to a total of 10 degrees
|
2012-12-19 11:06:20 -04:00
|
|
|
virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);
|
2012-11-05 00:29:00 -04:00
|
|
|
|
2014-02-08 02:52:03 -04:00
|
|
|
// helper trig value accessors
|
|
|
|
float cos_roll() const { return _cos_roll; }
|
|
|
|
float cos_pitch() const { return _cos_pitch; }
|
|
|
|
float cos_yaw() const { return _cos_yaw; }
|
|
|
|
float sin_roll() const { return _sin_roll; }
|
|
|
|
float sin_pitch() const { return _sin_pitch; }
|
|
|
|
float sin_yaw() const { return _sin_yaw; }
|
|
|
|
|
2013-07-19 22:11:57 -03:00
|
|
|
// for holding parameters
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
// these are public for ArduCopter
|
2013-03-29 06:42:26 -03:00
|
|
|
AP_Float _kp_yaw;
|
2012-08-21 23:19:51 -03:00
|
|
|
AP_Float _kp;
|
|
|
|
AP_Float gps_gain;
|
2013-07-19 22:11:57 -03:00
|
|
|
|
2014-01-01 22:47:40 -04:00
|
|
|
// return secondary attitude solution if available, as eulers in radians
|
|
|
|
virtual bool get_secondary_attitude(Vector3f &eulers) { return false; }
|
|
|
|
|
|
|
|
// return secondary position solution if available
|
|
|
|
virtual bool get_secondary_position(struct Location &loc) { return false; }
|
|
|
|
|
2014-01-02 07:06:10 -04:00
|
|
|
// get the home location. This is const to prevent any changes to
|
|
|
|
// home without telling AHRS about the change
|
|
|
|
const struct Location &get_home(void) const { return _home; }
|
|
|
|
|
|
|
|
// set the home location in 10e7 degrees. This should be called
|
|
|
|
// when the vehicle is at this position. It is assumed that the
|
|
|
|
// current barometer and GPS altitudes correspond to this altitude
|
2014-03-30 08:00:25 -03:00
|
|
|
virtual void set_home(const Location &loc) = 0;
|
2014-01-02 07:06:10 -04:00
|
|
|
|
2014-01-03 20:15:34 -04:00
|
|
|
// return true if the AHRS object supports inertial navigation,
|
|
|
|
// with very accurate position and velocity
|
|
|
|
virtual bool have_inertial_nav(void) const { return false; }
|
|
|
|
|
2014-02-26 18:41:28 -04:00
|
|
|
// return the active accelerometer instance
|
|
|
|
uint8_t get_active_accel_instance(void) const { return _active_accel_instance; }
|
|
|
|
|
2014-05-15 04:09:18 -03:00
|
|
|
// is the AHRS subsystem healthy?
|
|
|
|
virtual bool healthy(void) = 0;
|
|
|
|
|
2014-10-02 01:43:46 -03:00
|
|
|
// true if the AHRS has completed initialisation
|
|
|
|
virtual bool initialised(void) const { return true; };
|
2014-09-29 05:37:14 -03:00
|
|
|
|
2013-07-19 22:11:57 -03:00
|
|
|
protected:
|
2014-04-21 04:10:27 -03:00
|
|
|
AHRS_VehicleClass _vehicle_class;
|
|
|
|
|
2013-07-19 22:11:57 -03:00
|
|
|
// settable parameters
|
|
|
|
AP_Float beta;
|
2012-08-21 23:19:51 -03:00
|
|
|
AP_Int8 _gps_use;
|
2012-09-07 22:27:12 -03:00
|
|
|
AP_Int8 _wind_max;
|
2013-01-13 01:03:35 -04:00
|
|
|
AP_Int8 _board_orientation;
|
2013-05-04 23:47:49 -03:00
|
|
|
AP_Int8 _gps_minsats;
|
2013-11-04 00:50:33 -04:00
|
|
|
AP_Int8 _gps_delay;
|
2014-01-01 22:05:28 -04:00
|
|
|
AP_Int8 _ekf_use;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
2013-05-06 01:31:49 -03:00
|
|
|
// flags structure
|
|
|
|
struct ahrs_flags {
|
|
|
|
uint8_t have_initial_yaw : 1; // whether the yaw value has been intialised with a reference
|
|
|
|
uint8_t fast_ground_gains : 1; // should we raise the gain on the accelerometers for faster convergence, used when disarmed for ArduCopter
|
|
|
|
uint8_t fly_forward : 1; // 1 if we can assume the aircraft will be flying forward on its X axis
|
|
|
|
uint8_t correct_centrifugal : 1; // 1 if we should correct for centrifugal forces (allows arducopter to turn this off when motors are disarmed)
|
2013-05-23 22:21:23 -03:00
|
|
|
uint8_t wind_estimation : 1; // 1 if we should do wind estimation
|
2014-02-18 19:52:24 -04:00
|
|
|
uint8_t armed : 1; // 1 if we are armed for flight
|
2013-05-06 01:31:49 -03:00
|
|
|
} _flags;
|
2012-08-12 22:08:10 -03:00
|
|
|
|
2014-02-08 02:52:03 -04:00
|
|
|
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
|
|
|
|
// should be called after _dcm_matrix is updated
|
|
|
|
void update_trig(void);
|
|
|
|
|
2014-10-14 23:18:08 -03:00
|
|
|
// update roll_sensor, pitch_sensor and yaw_sensor
|
|
|
|
void update_cd_values(void);
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// pointer to compass object, if available
|
|
|
|
Compass * _compass;
|
2012-03-19 03:34:12 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// pointer to airspeed object, if available
|
|
|
|
AP_Airspeed * _airspeed;
|
2012-08-10 19:57:32 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// time in microseconds of last compass update
|
|
|
|
uint32_t _compass_last_update;
|
2012-03-19 03:34:12 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
|
|
|
|
// IMU under us without our noticing.
|
2013-11-03 23:34:32 -04:00
|
|
|
AP_InertialSensor &_ins;
|
2014-01-02 02:06:30 -04:00
|
|
|
AP_Baro &_baro;
|
2014-03-30 08:00:25 -03:00
|
|
|
const AP_GPS &_gps;
|
2012-11-05 00:29:00 -04:00
|
|
|
|
|
|
|
// a vector to capture the difference between the controller and body frames
|
|
|
|
AP_Vector3f _trim;
|
2012-03-19 03:34:12 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// the limit of the gyro drift claimed by the sensors, in
|
|
|
|
// radians/s/s
|
|
|
|
float _gyro_drift_limit;
|
2012-04-15 21:26:16 -03:00
|
|
|
|
2012-12-12 03:22:56 -04:00
|
|
|
// accelerometer values in the earth frame in m/s/s
|
2014-02-26 18:41:28 -04:00
|
|
|
Vector3f _accel_ef[INS_MAX_INSTANCES];
|
2012-12-12 03:22:56 -04:00
|
|
|
|
2013-03-29 06:42:26 -03:00
|
|
|
// Declare filter states for HPF and LPF used by complementary
|
|
|
|
// filter in AP_AHRS::groundspeed_vector
|
2013-05-12 22:24:48 -03:00
|
|
|
Vector2f _lp; // ground vector low-pass filter
|
|
|
|
Vector2f _hp; // ground vector high-pass filter
|
|
|
|
Vector2f _lastGndVelADS; // previous HPF input
|
2014-02-08 02:52:03 -04:00
|
|
|
|
2014-01-02 07:06:10 -04:00
|
|
|
// reference position for NED positions
|
|
|
|
struct Location _home;
|
|
|
|
|
2014-02-08 02:52:03 -04:00
|
|
|
// helper trig variables
|
|
|
|
float _cos_roll, _cos_pitch, _cos_yaw;
|
|
|
|
float _sin_roll, _sin_pitch, _sin_yaw;
|
2014-02-26 18:41:28 -04:00
|
|
|
|
|
|
|
// which accelerometer instance is active
|
|
|
|
uint8_t _active_accel_instance;
|
2013-05-12 22:24:48 -03:00
|
|
|
};
|
2012-03-19 03:34:12 -03:00
|
|
|
|
|
|
|
#include <AP_AHRS_DCM.h>
|
2014-01-01 21:15:58 -04:00
|
|
|
#include <AP_AHRS_NavEKF.h>
|
2012-03-19 03:34:12 -03:00
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
#endif // __AP_AHRS_H__
|