|
|
|
@ -43,8 +43,8 @@
@@ -43,8 +43,8 @@
|
|
|
|
|
#include <matrix/matrix/math.hpp> |
|
|
|
|
#include <lib/geo/geo.h> |
|
|
|
|
#include "RingBuffer.h" |
|
|
|
|
|
|
|
|
|
struct gps_message { |
|
|
|
|
namespace estimator { |
|
|
|
|
struct gps_message { |
|
|
|
|
uint64_t time_usec; |
|
|
|
|
int32_t lat; // Latitude in 1E-7 degrees
|
|
|
|
|
int32_t lon; // Longitude in 1E-7 degrees
|
|
|
|
@ -59,9 +59,62 @@ struct gps_message {
@@ -59,9 +59,62 @@ struct gps_message {
|
|
|
|
|
bool vel_ned_valid; // GPS ground speed is valid
|
|
|
|
|
uint8_t nsats; // number of satellites used
|
|
|
|
|
float gdop; // geometric dilution of precision
|
|
|
|
|
}; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
typedef matrix::Vector<float, 2> Vector2f; |
|
|
|
|
typedef matrix::Vector<float, 3> Vector3f; |
|
|
|
|
typedef matrix::Quaternion<float> Quaternion; |
|
|
|
|
typedef matrix::Matrix<float, 3, 3> Matrix3f; |
|
|
|
|
|
|
|
|
|
struct outputSample { |
|
|
|
|
Quaternion quat_nominal; |
|
|
|
|
Vector3f vel; |
|
|
|
|
Vector3f pos; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct imuSample { |
|
|
|
|
Vector3f delta_ang; |
|
|
|
|
Vector3f delta_vel; |
|
|
|
|
float delta_ang_dt; |
|
|
|
|
float delta_vel_dt; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct parameters { |
|
|
|
|
struct gpsSample { |
|
|
|
|
Vector2f pos; |
|
|
|
|
float hgt; |
|
|
|
|
Vector3f vel; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct magSample { |
|
|
|
|
Vector3f mag; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct baroSample { |
|
|
|
|
float hgt; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct rangeSample { |
|
|
|
|
float rng; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct airspeedSample { |
|
|
|
|
float airspeed; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct flowSample { |
|
|
|
|
Vector2f flowRadXY; |
|
|
|
|
Vector2f flowRadXYcomp; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct parameters { |
|
|
|
|
float mag_delay_ms = 0.0f; |
|
|
|
|
float baro_delay_ms = 0.0f; |
|
|
|
|
float gps_delay_ms = 200.0f; |
|
|
|
@ -101,10 +154,13 @@ struct parameters {
@@ -101,10 +154,13 @@ struct parameters {
|
|
|
|
|
float req_gdop = 2.0f; // maximum acceptable geometric dilution of precision
|
|
|
|
|
float req_hdrift = 0.3f; // maximum acceptable horizontal drift speed
|
|
|
|
|
float req_vdrift = 0.5f; // maximum acceptable vertical drift speed
|
|
|
|
|
}; |
|
|
|
|
}; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
using namespace estimator; |
|
|
|
|
class EstimatorBase |
|
|
|
|
{ |
|
|
|
|
|
|
|
|
|
public: |
|
|
|
|
EstimatorBase(); |
|
|
|
|
~EstimatorBase(); |
|
|
|
@ -181,13 +237,44 @@ public:
@@ -181,13 +237,44 @@ public:
|
|
|
|
|
// set vehicle arm status data
|
|
|
|
|
void set_arm_status(bool data){ _vehicle_armed = data; } |
|
|
|
|
|
|
|
|
|
void printIMU(struct imuSample *data); |
|
|
|
|
void printStoredIMU(); |
|
|
|
|
void printQuaternion(Quaternion &q); |
|
|
|
|
void print_imu_avg_time(); |
|
|
|
|
void printMag(struct magSample *data); |
|
|
|
|
void printStoredMag(); |
|
|
|
|
void printBaro(struct baroSample *data); |
|
|
|
|
void printStoredBaro(); |
|
|
|
|
void printGps(struct gpsSample *data); |
|
|
|
|
void printStoredGps(); |
|
|
|
|
|
|
|
|
|
protected: |
|
|
|
|
bool position_is_valid(); |
|
|
|
|
|
|
|
|
|
typedef matrix::Vector<float, 2> Vector2f; |
|
|
|
|
typedef matrix::Vector<float, 3> Vector3f; |
|
|
|
|
typedef matrix::Quaternion<float> Quaternion; |
|
|
|
|
typedef matrix::Matrix<float, 3, 3> Matrix3f; |
|
|
|
|
|
|
|
|
|
void copy_quaternion(float *quat) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 4; i++) { |
|
|
|
|
quat[i] = _output_new.quat_nominal(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_velocity(float *vel) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 3; i++) { |
|
|
|
|
vel[i] = _output_new.vel(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_position(float *pos) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 3; i++) { |
|
|
|
|
pos[i] = _output_new.pos(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_timestamp(uint64_t *time_us) |
|
|
|
|
{ |
|
|
|
|
*time_us = _imu_time_last; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
protected: |
|
|
|
|
|
|
|
|
|
struct stateSample { |
|
|
|
|
Vector3f ang_error; |
|
|
|
@ -202,54 +289,6 @@ protected:
@@ -202,54 +289,6 @@ protected:
|
|
|
|
|
Quaternion quat_nominal; |
|
|
|
|
} _state; |
|
|
|
|
|
|
|
|
|
struct outputSample { |
|
|
|
|
Quaternion quat_nominal; |
|
|
|
|
Vector3f vel; |
|
|
|
|
Vector3f pos; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct imuSample { |
|
|
|
|
Vector3f delta_ang; |
|
|
|
|
Vector3f delta_vel; |
|
|
|
|
float delta_ang_dt; |
|
|
|
|
float delta_vel_dt; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct gpsSample { |
|
|
|
|
Vector2f pos; |
|
|
|
|
float hgt; |
|
|
|
|
Vector3f vel; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct magSample { |
|
|
|
|
Vector3f mag; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct baroSample { |
|
|
|
|
float hgt; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct rangeSample { |
|
|
|
|
float rng; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct airspeedSample { |
|
|
|
|
float airspeed; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct flowSample { |
|
|
|
|
Vector2f flowRadXY; |
|
|
|
|
Vector2f flowRadXYcomp; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
parameters _params; // filter parameters
|
|
|
|
|
|
|
|
|
|
static const uint8_t OBS_BUFFER_LENGTH = 10; |
|
|
|
@ -317,43 +356,7 @@ protected:
@@ -317,43 +356,7 @@ protected:
|
|
|
|
|
} _fault_status; |
|
|
|
|
|
|
|
|
|
void initialiseVariables(uint64_t timestamp); |
|
|
|
|
|
|
|
|
|
public: |
|
|
|
|
void printIMU(struct imuSample *data); |
|
|
|
|
void printStoredIMU(); |
|
|
|
|
void printQuaternion(Quaternion &q); |
|
|
|
|
void print_imu_avg_time(); |
|
|
|
|
void printMag(struct magSample *data); |
|
|
|
|
void printStoredMag(); |
|
|
|
|
void printBaro(struct baroSample *data); |
|
|
|
|
void printStoredBaro(); |
|
|
|
|
void printGps(struct gpsSample *data); |
|
|
|
|
void printStoredGps(); |
|
|
|
|
|
|
|
|
|
bool position_is_valid(); |
|
|
|
|
|
|
|
|
|
void copy_quaternion(float *quat) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 4; i++) { |
|
|
|
|
quat[i] = _output_new.quat_nominal(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_velocity(float *vel) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 3; i++) { |
|
|
|
|
vel[i] = _output_new.vel(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_position(float *pos) |
|
|
|
|
{ |
|
|
|
|
for (unsigned i = 0; i < 3; i++) { |
|
|
|
|
pos[i] = _output_new.pos(i); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
void copy_timestamp(uint64_t *time_us) |
|
|
|
|
{ |
|
|
|
|
*time_us = _imu_time_last; |
|
|
|
|
} |
|
|
|
|
bool _vehicle_armed = false; // vehicle arm status used to turn off funtionality used on the ground
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
}; |
|
|
|
|