2014-01-01 21:15:58 -04: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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* NavEKF based AHRS (Attitude Heading Reference System) interface for
|
|
|
|
* ArduPilot
|
|
|
|
*
|
|
|
|
*/
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_AHRS.h"
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
2014-01-01 21:15:58 -04:00
|
|
|
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
|
2014-01-01 22:05:28 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-01-01 21:15:58 -04:00
|
|
|
// return the smoothed gyro vector corrected for drift
|
2014-07-13 08:56:39 -03:00
|
|
|
const Vector3f &AP_AHRS_NavEKF::get_gyro(void) const
|
2014-01-01 21:15:58 -04:00
|
|
|
{
|
2014-04-15 17:21:12 -03:00
|
|
|
if (!using_EKF()) {
|
|
|
|
return AP_AHRS_DCM::get_gyro();
|
|
|
|
}
|
2014-07-13 08:56:39 -03:00
|
|
|
return _gyro_estimate;
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
const Matrix3f &AP_AHRS_NavEKF::get_dcm_matrix(void) const
|
|
|
|
{
|
2014-01-04 00:21:24 -04:00
|
|
|
if (!using_EKF()) {
|
2014-01-01 22:05:28 -04:00
|
|
|
return AP_AHRS_DCM::get_dcm_matrix();
|
|
|
|
}
|
|
|
|
return _dcm_matrix;
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
const Vector3f &AP_AHRS_NavEKF::get_gyro_drift(void) const
|
|
|
|
{
|
2014-07-13 08:56:39 -03:00
|
|
|
if (!using_EKF()) {
|
|
|
|
return AP_AHRS_DCM::get_gyro_drift();
|
|
|
|
}
|
|
|
|
return _gyro_bias;
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
2014-10-28 08:22:48 -03:00
|
|
|
// reset the current gyro drift estimate
|
|
|
|
// should be called if gyro offsets are recalculated
|
|
|
|
void AP_AHRS_NavEKF::reset_gyro_drift(void)
|
|
|
|
{
|
|
|
|
// update DCM
|
|
|
|
AP_AHRS_DCM::reset_gyro_drift();
|
|
|
|
|
2014-10-28 22:20:43 -03:00
|
|
|
// reset the EKF gyro bias states
|
|
|
|
EKF.resetGyroBias();
|
2014-10-28 08:22:48 -03:00
|
|
|
}
|
|
|
|
|
2014-01-01 21:15:58 -04:00
|
|
|
void AP_AHRS_NavEKF::update(void)
|
|
|
|
{
|
2014-10-14 21:15:33 -03:00
|
|
|
// we need to restore the old DCM attitude values as these are
|
|
|
|
// used internally in DCM to calculate error values for gyro drift
|
|
|
|
// correction
|
|
|
|
roll = _dcm_attitude.x;
|
|
|
|
pitch = _dcm_attitude.y;
|
|
|
|
yaw = _dcm_attitude.z;
|
2014-10-14 23:18:08 -03:00
|
|
|
update_cd_values();
|
2014-10-14 21:15:33 -03:00
|
|
|
|
2014-01-01 21:15:58 -04:00
|
|
|
AP_AHRS_DCM::update();
|
2014-01-01 22:47:40 -04:00
|
|
|
|
|
|
|
// keep DCM attitude available for get_secondary_attitude()
|
|
|
|
_dcm_attitude(roll, pitch, yaw);
|
|
|
|
|
2014-01-01 22:05:28 -04:00
|
|
|
if (!ekf_started) {
|
2015-04-21 22:21:44 -03:00
|
|
|
// wait 1 second for DCM to output a valid tilt error estimate
|
2014-10-28 21:55:53 -03:00
|
|
|
if (start_time_ms == 0) {
|
|
|
|
start_time_ms = hal.scheduler->millis();
|
|
|
|
}
|
2015-04-07 03:37:50 -03:00
|
|
|
if (hal.scheduler->millis() - start_time_ms > startup_delay_ms) {
|
|
|
|
ekf_started = EKF.InitialiseFilterDynamic();
|
2014-01-01 22:05:28 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
if (ekf_started) {
|
|
|
|
EKF.UpdateFilter();
|
2014-01-04 01:00:47 -04:00
|
|
|
EKF.getRotationBodyToNED(_dcm_matrix);
|
2014-01-02 01:16:29 -04:00
|
|
|
if (using_EKF()) {
|
2014-01-01 22:05:28 -04:00
|
|
|
Vector3f eulers;
|
|
|
|
EKF.getEulerAngles(eulers);
|
|
|
|
roll = eulers.x;
|
|
|
|
pitch = eulers.y;
|
|
|
|
yaw = eulers.z;
|
2014-10-14 23:18:08 -03:00
|
|
|
|
|
|
|
update_cd_values();
|
2014-02-13 04:53:14 -04:00
|
|
|
update_trig();
|
2014-07-13 08:56:39 -03:00
|
|
|
|
|
|
|
// keep _gyro_bias for get_gyro_drift()
|
|
|
|
EKF.getGyroBias(_gyro_bias);
|
|
|
|
_gyro_bias = -_gyro_bias;
|
|
|
|
|
|
|
|
// calculate corrected gryo estimate for get_gyro()
|
|
|
|
_gyro_estimate.zero();
|
|
|
|
uint8_t healthy_count = 0;
|
|
|
|
for (uint8_t i=0; i<_ins.get_gyro_count(); i++) {
|
2015-05-09 08:00:49 -03:00
|
|
|
if (_ins.get_gyro_health(i) && healthy_count < 2) {
|
2014-07-13 08:56:39 -03:00
|
|
|
_gyro_estimate += _ins.get_gyro(i);
|
|
|
|
healthy_count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (healthy_count > 1) {
|
|
|
|
_gyro_estimate /= healthy_count;
|
|
|
|
}
|
|
|
|
_gyro_estimate += _gyro_bias;
|
2014-10-31 19:07:18 -03:00
|
|
|
|
2015-03-28 04:08:11 -03:00
|
|
|
float abias1, abias2;
|
|
|
|
EKF.getAccelZBias(abias1, abias2);
|
|
|
|
|
2014-10-31 19:07:18 -03:00
|
|
|
// update _accel_ef_ekf
|
|
|
|
for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
|
2015-03-28 04:08:11 -03:00
|
|
|
Vector3f accel = _ins.get_accel(i);
|
|
|
|
if (i==0) {
|
|
|
|
accel.z -= abias1;
|
|
|
|
} else if (i==1) {
|
|
|
|
accel.z -= abias2;
|
|
|
|
}
|
2014-10-31 19:07:18 -03:00
|
|
|
if (_ins.get_accel_health(i)) {
|
2015-03-28 04:08:11 -03:00
|
|
|
_accel_ef_ekf[i] = _dcm_matrix * accel;
|
2014-10-31 19:07:18 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-08-01 05:38:22 -03:00
|
|
|
if(_ins.use_accel(0) && _ins.use_accel(1)) {
|
2015-03-28 04:08:11 -03:00
|
|
|
float IMU1_weighting;
|
|
|
|
EKF.getIMU1Weighting(IMU1_weighting);
|
|
|
|
_accel_ef_ekf_blended = _accel_ef_ekf[0] * IMU1_weighting + _accel_ef_ekf[1] * (1.0f-IMU1_weighting);
|
|
|
|
} else {
|
2015-08-01 05:19:26 -03:00
|
|
|
_accel_ef_ekf_blended = _accel_ef_ekf[_ins.get_primary_accel()];
|
2015-03-28 04:08:11 -03:00
|
|
|
}
|
2014-01-01 22:05:28 -04:00
|
|
|
}
|
|
|
|
}
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
2014-10-31 19:07:18 -03:00
|
|
|
// accelerometer values in the earth frame in m/s/s
|
|
|
|
const Vector3f &AP_AHRS_NavEKF::get_accel_ef(uint8_t i) const
|
|
|
|
{
|
|
|
|
if(!using_EKF()) {
|
|
|
|
return AP_AHRS_DCM::get_accel_ef(i);
|
|
|
|
}
|
|
|
|
return _accel_ef_ekf[i];
|
|
|
|
}
|
|
|
|
|
|
|
|
// blended accelerometer values in the earth frame in m/s/s
|
|
|
|
const Vector3f &AP_AHRS_NavEKF::get_accel_ef_blended(void) const
|
|
|
|
{
|
|
|
|
if(!using_EKF()) {
|
|
|
|
return AP_AHRS_DCM::get_accel_ef_blended();
|
|
|
|
}
|
|
|
|
return _accel_ef_ekf_blended;
|
|
|
|
}
|
|
|
|
|
2014-01-01 21:15:58 -04:00
|
|
|
void AP_AHRS_NavEKF::reset(bool recover_eulers)
|
|
|
|
{
|
|
|
|
AP_AHRS_DCM::reset(recover_eulers);
|
2014-01-01 22:05:28 -04:00
|
|
|
if (ekf_started) {
|
2015-03-28 14:52:22 -03:00
|
|
|
ekf_started = EKF.InitialiseFilterBootstrap();
|
2014-01-01 22:05:28 -04:00
|
|
|
}
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// reset the current attitude, used on new IMU calibration
|
|
|
|
void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
|
|
|
|
{
|
|
|
|
AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw);
|
2014-01-01 22:05:28 -04:00
|
|
|
if (ekf_started) {
|
2015-03-28 14:52:22 -03:00
|
|
|
ekf_started = EKF.InitialiseFilterBootstrap();
|
2014-01-01 22:05:28 -04:00
|
|
|
}
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// dead-reckoning support
|
2014-10-17 22:14:34 -03:00
|
|
|
bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
|
2014-01-01 21:15:58 -04:00
|
|
|
{
|
2015-02-20 19:12:53 -04:00
|
|
|
Vector3f ned_pos;
|
|
|
|
if (using_EKF() && EKF.getLLH(loc) && EKF.getPosNED(ned_pos)) {
|
|
|
|
// fixup altitude using relative position from AHRS home, not
|
|
|
|
// EKF origin
|
|
|
|
loc.alt = get_home().alt - ned_pos.z*100;
|
2014-01-02 01:16:29 -04:00
|
|
|
return true;
|
2014-01-01 22:05:28 -04:00
|
|
|
}
|
2014-01-01 21:15:58 -04:00
|
|
|
return AP_AHRS_DCM::get_position(loc);
|
|
|
|
}
|
|
|
|
|
2014-01-01 22:05:28 -04:00
|
|
|
// status reporting of estimated errors
|
2015-04-21 10:41:46 -03:00
|
|
|
float AP_AHRS_NavEKF::get_error_rp(void) const
|
2014-01-01 21:15:58 -04:00
|
|
|
{
|
|
|
|
return AP_AHRS_DCM::get_error_rp();
|
|
|
|
}
|
|
|
|
|
2015-04-21 10:41:46 -03:00
|
|
|
float AP_AHRS_NavEKF::get_error_yaw(void) const
|
2014-01-01 21:15:58 -04:00
|
|
|
{
|
|
|
|
return AP_AHRS_DCM::get_error_yaw();
|
|
|
|
}
|
|
|
|
|
|
|
|
// return a wind estimation vector, in m/s
|
|
|
|
Vector3f AP_AHRS_NavEKF::wind_estimate(void)
|
|
|
|
{
|
2014-04-13 06:42:49 -03:00
|
|
|
if (!using_EKF()) {
|
2014-04-09 17:49:13 -03:00
|
|
|
// EKF does not estimate wind speed when there is no airspeed
|
|
|
|
// sensor active
|
2014-01-01 22:05:28 -04:00
|
|
|
return AP_AHRS_DCM::wind_estimate();
|
|
|
|
}
|
|
|
|
Vector3f wind;
|
|
|
|
EKF.getWind(wind);
|
|
|
|
return wind;
|
2014-01-01 21:15:58 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// return an airspeed estimate if available. return true
|
|
|
|
// if we have an estimate
|
2014-02-24 21:43:59 -04:00
|
|
|
bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret) const
|
2014-01-01 21:15:58 -04:00
|
|
|
{
|
|
|
|
return AP_AHRS_DCM::airspeed_estimate(airspeed_ret);
|
|
|
|
}
|
|
|
|
|
|
|
|
// true if compass is being used
|
|
|
|
bool AP_AHRS_NavEKF::use_compass(void)
|
|
|
|
{
|
2014-08-24 08:00:56 -03:00
|
|
|
if (using_EKF()) {
|
|
|
|
return EKF.use_compass();
|
|
|
|
}
|
2014-01-01 21:15:58 -04:00
|
|
|
return AP_AHRS_DCM::use_compass();
|
|
|
|
}
|
|
|
|
|
2014-01-01 22:47:40 -04:00
|
|
|
|
|
|
|
// return secondary attitude solution if available, as eulers in radians
|
|
|
|
bool AP_AHRS_NavEKF::get_secondary_attitude(Vector3f &eulers)
|
|
|
|
{
|
2014-01-02 01:16:29 -04:00
|
|
|
if (using_EKF()) {
|
2014-01-01 22:47:40 -04:00
|
|
|
// return DCM attitude
|
|
|
|
eulers = _dcm_attitude;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (ekf_started) {
|
|
|
|
// EKF is secondary
|
|
|
|
EKF.getEulerAngles(eulers);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
// no secondary available
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return secondary position solution if available
|
|
|
|
bool AP_AHRS_NavEKF::get_secondary_position(struct Location &loc)
|
|
|
|
{
|
2014-01-02 01:16:29 -04:00
|
|
|
if (using_EKF()) {
|
2014-01-01 22:47:40 -04:00
|
|
|
// return DCM position
|
|
|
|
AP_AHRS_DCM::get_position(loc);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (ekf_started) {
|
|
|
|
// EKF is secondary
|
|
|
|
EKF.getLLH(loc);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
// no secondary available
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2014-01-01 23:25:41 -04:00
|
|
|
// EKF has a better ground speed vector estimate
|
|
|
|
Vector2f AP_AHRS_NavEKF::groundspeed_vector(void)
|
|
|
|
{
|
2014-01-02 01:16:29 -04:00
|
|
|
if (!using_EKF()) {
|
2014-01-01 23:25:41 -04:00
|
|
|
return AP_AHRS_DCM::groundspeed_vector();
|
|
|
|
}
|
|
|
|
Vector3f vec;
|
|
|
|
EKF.getVelNED(vec);
|
|
|
|
return Vector2f(vec.x, vec.y);
|
|
|
|
}
|
|
|
|
|
2014-03-30 08:00:25 -03:00
|
|
|
void AP_AHRS_NavEKF::set_home(const Location &loc)
|
2014-01-02 07:06:10 -04:00
|
|
|
{
|
2014-03-30 08:00:25 -03:00
|
|
|
AP_AHRS_DCM::set_home(loc);
|
2014-01-02 07:06:10 -04:00
|
|
|
}
|
|
|
|
|
2014-01-03 20:15:34 -04:00
|
|
|
// return true if inertial navigation is active
|
|
|
|
bool AP_AHRS_NavEKF::have_inertial_nav(void) const
|
|
|
|
{
|
|
|
|
return using_EKF();
|
|
|
|
}
|
|
|
|
|
2014-02-08 04:11:12 -04:00
|
|
|
// return a ground velocity in meters/second, North/East/Down
|
|
|
|
// order. Must only be called if have_inertial_nav() is true
|
|
|
|
bool AP_AHRS_NavEKF::get_velocity_NED(Vector3f &vec) const
|
2014-01-03 20:15:34 -04:00
|
|
|
{
|
|
|
|
if (using_EKF()) {
|
|
|
|
EKF.getVelNED(vec);
|
2014-02-08 04:11:12 -04:00
|
|
|
return true;
|
2014-01-03 20:15:34 -04:00
|
|
|
}
|
2014-02-08 04:11:12 -04:00
|
|
|
return false;
|
2014-01-03 20:15:34 -04:00
|
|
|
}
|
|
|
|
|
2014-02-08 04:11:12 -04:00
|
|
|
// return a relative ground position in meters/second, North/East/Down
|
|
|
|
// order. Must only be called if have_inertial_nav() is true
|
|
|
|
bool AP_AHRS_NavEKF::get_relative_position_NED(Vector3f &vec) const
|
2014-01-03 20:15:34 -04:00
|
|
|
{
|
2014-02-08 04:11:12 -04:00
|
|
|
if (using_EKF()) {
|
|
|
|
return EKF.getPosNED(vec);
|
2014-01-03 20:15:34 -04:00
|
|
|
}
|
2014-02-08 04:11:12 -04:00
|
|
|
return false;
|
2014-01-03 20:15:34 -04:00
|
|
|
}
|
|
|
|
|
2014-02-14 18:24:12 -04:00
|
|
|
bool AP_AHRS_NavEKF::using_EKF(void) const
|
|
|
|
{
|
2015-05-13 02:37:17 -03:00
|
|
|
uint8_t ekf_faults;
|
|
|
|
EKF.getFilterFaults(ekf_faults);
|
|
|
|
// If EKF is started we switch away if it reports unhealthy. This could be due to bad
|
|
|
|
// sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters
|
|
|
|
// an internal processing error, but not for bad sensor data.
|
|
|
|
bool ret = ekf_started && ((_ekf_use == EKF_USE_WITH_FALLBACK && EKF.healthy()) || (_ekf_use == EKF_USE_WITHOUT_FALLBACK && ekf_faults == 0));
|
2015-04-07 20:11:24 -03:00
|
|
|
if (!ret) {
|
|
|
|
return false;
|
|
|
|
}
|
2015-05-19 02:15:44 -03:00
|
|
|
|
|
|
|
if (_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
|
|
|
_vehicle_class == AHRS_VEHICLE_GROUND) {
|
|
|
|
nav_filter_status filt_state;
|
|
|
|
EKF.getFilterStatus(filt_state);
|
|
|
|
if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && _gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
|
|
|
// if the EKF is not fusing GPS and we have a 3D lock, then
|
|
|
|
// plane and rover would prefer to use the GPS position from
|
|
|
|
// DCM. This is a safety net while some issues with the EKF
|
|
|
|
// get sorted out
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!filt_state.flags.attitude ||
|
|
|
|
!filt_state.flags.horiz_vel ||
|
|
|
|
!filt_state.flags.vert_vel ||
|
|
|
|
!filt_state.flags.horiz_pos_abs ||
|
|
|
|
!filt_state.flags.vert_pos) {
|
|
|
|
return false;
|
|
|
|
}
|
2015-04-07 20:11:24 -03:00
|
|
|
}
|
|
|
|
return ret;
|
2014-02-14 18:24:12 -04:00
|
|
|
}
|
|
|
|
|
2014-05-15 04:09:18 -03:00
|
|
|
/*
|
|
|
|
check if the AHRS subsystem is healthy
|
|
|
|
*/
|
2015-01-31 22:31:24 -04:00
|
|
|
bool AP_AHRS_NavEKF::healthy(void) const
|
2014-05-15 04:09:18 -03:00
|
|
|
{
|
2015-05-13 02:37:17 -03:00
|
|
|
// If EKF is started we switch away if it reports unhealthy. This could be due to bad
|
|
|
|
// sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters
|
|
|
|
// an internal processing error, but not for bad sensor data.
|
|
|
|
if (_ekf_use != EKF_DO_NOT_USE) {
|
2015-05-19 02:11:31 -03:00
|
|
|
bool ret = ekf_started && EKF.healthy();
|
|
|
|
if (!ret) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
|
|
|
_vehicle_class == AHRS_VEHICLE_GROUND) &&
|
|
|
|
!using_EKF()) {
|
|
|
|
// on fixed wing we want to be using EKF to be considered
|
|
|
|
// healthy if EKF is enabled
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
2014-05-15 04:09:18 -03:00
|
|
|
}
|
|
|
|
return AP_AHRS_DCM::healthy();
|
|
|
|
}
|
|
|
|
|
2015-03-19 02:58:13 -03:00
|
|
|
void AP_AHRS_NavEKF::set_ekf_use(bool setting)
|
|
|
|
{
|
|
|
|
#if !AHRS_EKF_USE_ALWAYS
|
|
|
|
_ekf_use.set(setting);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2014-10-02 01:43:46 -03:00
|
|
|
// true if the AHRS has completed initialisation
|
|
|
|
bool AP_AHRS_NavEKF::initialised(void) const
|
2014-09-29 05:37:14 -03:00
|
|
|
{
|
2014-10-02 01:43:46 -03:00
|
|
|
// initialisation complete 10sec after ekf has started
|
|
|
|
return (ekf_started && (hal.scheduler->millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
|
|
|
|
};
|
2014-09-29 05:37:14 -03:00
|
|
|
|
2014-08-06 21:31:24 -03:00
|
|
|
// write optical flow data to EKF
|
2015-04-15 18:43:42 -03:00
|
|
|
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas)
|
2014-08-06 21:31:24 -03:00
|
|
|
{
|
2015-04-15 18:43:42 -03:00
|
|
|
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas);
|
2014-08-06 21:31:24 -03:00
|
|
|
}
|
2014-11-12 14:49:15 -04:00
|
|
|
|
|
|
|
// inhibit GPS useage
|
|
|
|
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
|
|
|
|
{
|
2014-11-15 19:36:33 -04:00
|
|
|
return EKF.setInhibitGPS();
|
2014-11-12 14:49:15 -04:00
|
|
|
}
|
2014-11-15 19:36:33 -04:00
|
|
|
|
|
|
|
// get speed limit
|
2014-11-15 21:42:30 -04:00
|
|
|
void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler)
|
2014-11-15 19:36:33 -04:00
|
|
|
{
|
2014-11-15 21:42:30 -04:00
|
|
|
EKF.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
|
2014-11-15 19:36:33 -04:00
|
|
|
}
|
|
|
|
|
2015-03-16 18:29:11 -03:00
|
|
|
// get compass offset estimates
|
|
|
|
// true if offsets are valid
|
|
|
|
bool AP_AHRS_NavEKF::getMagOffsets(Vector3f &magOffsets)
|
|
|
|
{
|
|
|
|
bool status = EKF.getMagOffsets(magOffsets);
|
|
|
|
return status;
|
|
|
|
}
|
|
|
|
|
2014-01-01 21:15:58 -04:00
|
|
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
2014-02-14 18:24:12 -04:00
|
|
|
|