2015-01-30 02:37:25 -04:00
|
|
|
/*
|
|
|
|
smaller EKF for simpler estimation applications
|
|
|
|
|
|
|
|
Converted from Matlab to C++ by Paul Riseborough
|
|
|
|
|
|
|
|
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/>.
|
|
|
|
*/
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2015-01-30 02:37:25 -04:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2016-11-27 00:18:00 -04:00
|
|
|
//#include <AP_NavEKF2/AP_NavEKF2.h>
|
2020-07-24 14:01:21 -03:00
|
|
|
#include "AP_Mount.h"
|
|
|
|
#if HAL_SOLO_GIMBAL_ENABLED
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Math/vectorN.h>
|
2015-01-30 02:37:25 -04:00
|
|
|
|
2015-12-30 20:00:28 -04:00
|
|
|
class SoloGimbalEKF
|
2015-01-30 02:37:25 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
typedef float ftype;
|
|
|
|
#if MATH_CHECK_INDEXES
|
|
|
|
typedef VectorN<ftype,13> Vector13;
|
|
|
|
#else
|
|
|
|
typedef ftype Vector13[13];
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// Constructor
|
2018-11-04 21:07:32 -04:00
|
|
|
SoloGimbalEKF();
|
2015-01-30 02:37:25 -04:00
|
|
|
|
|
|
|
// Run the EKF main loop once every time we receive sensor data
|
|
|
|
void RunEKF(float delta_time, const Vector3f &delta_angles, const Vector3f &delta_velocity, const Vector3f &joint_angles);
|
|
|
|
|
2015-12-30 20:00:28 -04:00
|
|
|
void reset();
|
|
|
|
|
2015-01-31 04:26:35 -04:00
|
|
|
// get gyro bias data
|
|
|
|
void getGyroBias(Vector3f &gyroBias) const;
|
|
|
|
|
2015-12-30 20:00:28 -04:00
|
|
|
// set gyro bias
|
|
|
|
void setGyroBias(const Vector3f &gyroBias);
|
|
|
|
|
2015-01-31 04:26:35 -04:00
|
|
|
// get quaternion data
|
|
|
|
void getQuat(Quaternion &quat) const;
|
|
|
|
|
2015-03-05 19:23:14 -04:00
|
|
|
// get filter alignment status - true is aligned
|
|
|
|
bool getStatus(void) const;
|
|
|
|
|
2015-01-30 02:37:25 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
// the states are available in two forms, either as a Vector13 or
|
|
|
|
// broken down as individual elements. Both are equivalent (same
|
|
|
|
// memory)
|
|
|
|
Vector13 states;
|
|
|
|
struct state_elements {
|
|
|
|
Vector3f angErr; // 0..2 rotation vector representing the growth in angle error since the last state correction (rad)
|
|
|
|
Vector3f velocity; // 3..5 NED velocity (m/s)
|
|
|
|
Vector3f delAngBias; // 6..8 estimated bias errors in the IMU delta angles
|
|
|
|
Quaternion quat; // 9..12 these states are used by the INS prediction only and are not used by the EKF state equations.
|
|
|
|
} &state;
|
|
|
|
|
|
|
|
// data from sensors
|
|
|
|
struct {
|
|
|
|
Vector3f delAng;
|
|
|
|
Vector3f delVel;
|
|
|
|
float gPhi;
|
|
|
|
float gPsi;
|
|
|
|
float gTheta;
|
|
|
|
} gSense;
|
|
|
|
|
|
|
|
float Cov[9][9]; // covariance matrix
|
|
|
|
Matrix3f Tsn; // Sensor to NED rotation matrix
|
2018-11-04 21:55:40 -04:00
|
|
|
float TiltCorrectionSquared; // Angle correction applied to tilt from last velocity fusion (rad)
|
2015-01-30 02:37:25 -04:00
|
|
|
bool newDataMag; // true when new magnetometer data is waiting to be used
|
|
|
|
uint32_t StartTime_ms; // time the EKF was started (msec)
|
|
|
|
bool FiltInit; // true when EKF is initialised
|
|
|
|
bool YawAligned; // true when EKF heading is initialised
|
|
|
|
float cosPhi;// = cosf(gSense.gPhi);
|
|
|
|
float cosTheta;// = cosf(gSense.gTheta);
|
|
|
|
float sinPhi;// = sinf(gSense.gPhi);
|
|
|
|
float sinTheta;// = sinf(gSense.gTheta);
|
|
|
|
float sinPsi;// = sinf(gSense.gPsi);
|
|
|
|
float cosPsi;// = cosf(gSense.gPsi);
|
|
|
|
uint32_t lastMagUpdate;
|
|
|
|
Vector3f magData;
|
|
|
|
|
|
|
|
uint32_t imuSampleTime_ms;
|
|
|
|
float dtIMU;
|
|
|
|
|
2015-12-30 20:00:28 -04:00
|
|
|
// States used for unwrapping of compass yaw error
|
|
|
|
float innovationIncrement;
|
|
|
|
float lastInnovation;
|
|
|
|
|
2015-01-30 02:37:25 -04:00
|
|
|
// state prediction
|
|
|
|
void predictStates();
|
|
|
|
|
|
|
|
// EKF covariance prediction
|
|
|
|
void predictCovariance();
|
|
|
|
|
|
|
|
// EKF velocity fusion
|
2015-12-30 20:00:28 -04:00
|
|
|
void fuseVelocity();
|
2015-01-30 02:37:25 -04:00
|
|
|
|
|
|
|
// read magnetometer data
|
|
|
|
void readMagData();
|
|
|
|
|
|
|
|
// EKF compass fusion
|
|
|
|
void fuseCompass();
|
|
|
|
|
|
|
|
// Perform an initial heading alignment using the magnetic field and assumed declination
|
|
|
|
void alignHeading();
|
|
|
|
|
|
|
|
// Calculate magnetic heading innovation
|
|
|
|
float calcMagHeadingInnov();
|
|
|
|
|
|
|
|
// Force symmmetry and non-negative diagonals on state covarinace matrix
|
|
|
|
void fixCovariance();
|
|
|
|
};
|
2020-07-24 14:01:21 -03:00
|
|
|
#endif // HAL_SOLO_GIMBAL_ENABLED
|