2015-11-19 13:08:04 -04:00
/****************************************************************************
*
* Copyright ( c ) 2013 Estimation and Control Library ( ECL ) . All rights reserved .
*
* Redistribution and use in source and binary forms , with or without
* modification , are permitted provided that the following conditions
* are met :
*
* 1. Redistributions of source code must retain the above copyright
* notice , this list of conditions and the following disclaimer .
* 2. Redistributions in binary form must reproduce the above copyright
* notice , this list of conditions and the following disclaimer in
* the documentation and / or other materials provided with the
* distribution .
* 3. Neither the name ECL nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission .
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* " AS IS " AND ANY EXPRESS OR IMPLIED WARRANTIES , INCLUDING , BUT NOT
* LIMITED TO , THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED . IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT , INDIRECT ,
* INCIDENTAL , SPECIAL , EXEMPLARY , OR CONSEQUENTIAL DAMAGES ( INCLUDING ,
* BUT NOT LIMITED TO , PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES ; LOSS
* OF USE , DATA , OR PROFITS ; OR BUSINESS INTERRUPTION ) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY , WHETHER IN CONTRACT , STRICT
* LIABILITY , OR TORT ( INCLUDING NEGLIGENCE OR OTHERWISE ) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE , EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
2016-01-31 03:37:34 -04:00
* @ file estimator_interface . cpp
2015-11-19 13:08:04 -04:00
* Definition of base class for attitude estimators
*
2015-12-06 07:57:43 -04:00
* @ author Roman Bast < bapstroman @ gmail . com >
2016-01-24 09:36:31 -04:00
* @ author Paul Riseborough < p_riseborough @ live . com . au >
2016-01-30 00:03:25 -04:00
* @ author Siddharth B Purohit < siddharthbharatpurohit @ gmail . com >
2015-11-19 13:08:04 -04:00
*/
2016-01-19 02:19:10 -04:00
# include <inttypes.h>
2015-11-19 13:08:04 -04:00
# include <math.h>
2016-06-02 12:29:22 -03:00
# include "../ecl.h"
2016-01-31 03:37:34 -04:00
# include "estimator_interface.h"
2016-02-17 21:33:18 -04:00
# include "mathlib.h"
2015-11-19 13:08:04 -04:00
2016-02-20 02:57:06 -04:00
EstimatorInterface : : EstimatorInterface ( ) :
2016-11-07 07:23:12 -04:00
_obs_buffer_length ( 10 ) ,
_imu_buffer_length ( 30 ) ,
2016-05-26 00:27:08 -03:00
_min_obs_interval_us ( 0 ) ,
2016-02-20 02:57:06 -04:00
_dt_imu_avg ( 0.0f ) ,
2017-01-09 08:50:41 -04:00
_mag_sample_delayed { } ,
_baro_sample_delayed { } ,
_gps_sample_delayed { } ,
_range_sample_delayed { } ,
_airspeed_sample_delayed { } ,
_flow_sample_delayed { } ,
_ev_sample_delayed { } ,
2016-02-20 02:57:06 -04:00
_imu_ticks ( 0 ) ,
_imu_updated ( false ) ,
_initialised ( false ) ,
_NED_origin_initialised ( false ) ,
_gps_speed_valid ( false ) ,
2016-02-27 00:42:22 -04:00
_gps_origin_eph ( 0.0f ) ,
_gps_origin_epv ( 0.0f ) ,
2017-01-09 08:50:41 -04:00
_pos_ref { } ,
2016-02-20 02:57:06 -04:00
_yaw_test_ratio ( 0.0f ) ,
2017-01-09 08:50:41 -04:00
_mag_test_ratio { } ,
_vel_pos_test_ratio { } ,
2016-10-05 02:52:21 -03:00
_tas_test_ratio ( 0.0f ) ,
_terr_test_ratio ( 0.0f ) ,
2017-01-04 05:44:07 -04:00
_beta_test_ratio ( 0.0f ) ,
2017-01-09 08:50:41 -04:00
_vibe_metrics { } ,
2016-02-20 02:57:06 -04:00
_time_last_imu ( 0 ) ,
_time_last_gps ( 0 ) ,
_time_last_mag ( 0 ) ,
_time_last_baro ( 0 ) ,
_time_last_range ( 0 ) ,
_time_last_airspeed ( 0 ) ,
2016-03-20 05:41:40 -03:00
_time_last_ext_vision ( 0 ) ,
2017-01-04 05:44:07 -04:00
_time_last_optflow ( 0 ) ,
2016-02-20 02:57:06 -04:00
_mag_declination_gps ( 0.0f ) ,
_mag_declination_to_save_deg ( 0.0f )
2015-11-19 13:08:04 -04:00
{
2016-10-18 01:24:43 -03:00
_delta_ang_prev . setZero ( ) ;
_delta_vel_prev . setZero ( ) ;
2015-11-19 13:08:04 -04:00
}
2016-01-31 03:37:34 -04:00
EstimatorInterface : : ~ EstimatorInterface ( )
2015-11-19 13:08:04 -04:00
{
}
2015-12-07 04:26:30 -04:00
// Accumulate imu data and store to buffer at desired rate
2016-01-31 04:01:44 -04:00
void EstimatorInterface : : setIMUData ( uint64_t time_usec , uint64_t delta_ang_dt , uint64_t delta_vel_dt , float * delta_ang ,
float * delta_vel )
2015-11-19 13:08:04 -04:00
{
if ( ! _initialised ) {
2016-01-30 16:42:24 -04:00
init ( time_usec ) ;
2015-11-19 13:08:04 -04:00
_initialised = true ;
}
float dt = ( float ) ( time_usec - _time_last_imu ) / 1000 / 1000 ;
dt = math : : max ( dt , 1.0e-4 f ) ;
dt = math : : min ( dt , 0.02f ) ;
_time_last_imu = time_usec ;
2015-12-22 06:22:17 -04:00
if ( _time_last_imu > 0 ) {
2015-11-19 13:08:04 -04:00
_dt_imu_avg = 0.8f * _dt_imu_avg + 0.2f * dt ;
}
// copy data
imuSample imu_sample_new = { } ;
2017-01-04 06:05:43 -04:00
memcpy ( & imu_sample_new . delta_ang , delta_ang , sizeof ( imu_sample_new . delta_ang ) ) ;
memcpy ( & imu_sample_new . delta_vel , delta_vel , sizeof ( imu_sample_new . delta_vel ) ) ;
2015-11-19 13:08:04 -04:00
2016-05-26 00:27:08 -03:00
// convert time from us to secs
2015-11-19 13:08:04 -04:00
imu_sample_new . delta_ang_dt = delta_ang_dt / 1e6 f ;
imu_sample_new . delta_vel_dt = delta_vel_dt / 1e6 f ;
imu_sample_new . time_us = time_usec ;
_imu_ticks + + ;
2016-10-18 01:24:43 -03:00
// calculate a metric which indicates the amount of coning vibration
Vector3f temp = cross_product ( imu_sample_new . delta_ang , _delta_ang_prev ) ;
_vibe_metrics [ 0 ] = 0.99f * _vibe_metrics [ 0 ] + 0.01f * temp . length ( ) ;
// calculate a metric which indiates the amount of high frequency gyro vibration
temp = imu_sample_new . delta_ang - _delta_ang_prev ;
_delta_ang_prev = imu_sample_new . delta_ang ;
_vibe_metrics [ 1 ] = 0.99f * _vibe_metrics [ 1 ] + 0.01f * temp . length ( ) ;
// calculate a metric which indicates the amount of high fequency accelerometer vibration
temp = imu_sample_new . delta_vel - _delta_vel_prev ;
_delta_vel_prev = imu_sample_new . delta_vel ;
_vibe_metrics [ 2 ] = 0.99f * _vibe_metrics [ 2 ] + 0.01f * temp . length ( ) ;
2016-05-26 00:27:08 -03:00
// accumulate and down-sample imu data and push to the buffer when new downsampled data becomes available
2016-01-30 00:03:25 -04:00
if ( collect_imu ( imu_sample_new ) ) {
_imu_buffer . push ( imu_sample_new ) ;
2015-11-19 13:08:04 -04:00
_imu_ticks = 0 ;
_imu_updated = true ;
2016-05-26 00:27:08 -03:00
// get the oldest data from the buffer
_imu_sample_delayed = _imu_buffer . get_oldest ( ) ;
2016-05-26 08:42:56 -03:00
// calculate the minimum interval between observations required to guarantee no loss of data
// this will occur if data is overwritten before its time stamp falls behind the fusion time horizon
2016-11-07 07:23:12 -04:00
_min_obs_interval_us = ( _imu_sample_new . time_us - _imu_sample_delayed . time_us ) / ( _obs_buffer_length - 1 ) ;
2016-05-26 00:27:08 -03:00
2015-11-19 13:08:04 -04:00
} else {
_imu_updated = false ;
2016-05-26 00:27:08 -03:00
}
2015-11-19 13:08:04 -04:00
}
2016-01-31 03:37:34 -04:00
void EstimatorInterface : : setMagData ( uint64_t time_usec , float * data )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_mag > _min_obs_interval_us ) {
2015-11-19 13:08:04 -04:00
magSample mag_sample_new = { } ;
mag_sample_new . time_us = time_usec - _params . mag_delay_ms * 1000 ;
2016-05-22 12:40:43 -03:00
mag_sample_new . time_us - = FILTER_UPDATE_PERIOD_MS * 1000 / 2 ;
2015-12-26 02:52:14 -04:00
_time_last_mag = time_usec ;
2015-11-19 13:08:04 -04:00
2017-01-04 06:05:43 -04:00
memcpy ( & mag_sample_new . mag , data , sizeof ( mag_sample_new . mag ) ) ;
2015-11-19 13:08:04 -04:00
_mag_buffer . push ( mag_sample_new ) ;
}
}
2016-01-31 03:37:34 -04:00
void EstimatorInterface : : setGpsData ( uint64_t time_usec , struct gps_message * gps )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
if ( ! _initialised ) {
return ;
}
// limit data rate to prevent data being lost
2016-05-23 18:55:09 -03:00
bool need_gps = ( _params . fusion_mode & MASK_USE_GPS ) | | ( _params . vdist_sensor_type = = VDIST_SENSOR_GPS ) ;
2016-05-26 00:27:08 -03:00
if ( ( ( time_usec - _time_last_gps ) > _min_obs_interval_us ) & & need_gps ) {
2015-11-19 13:08:04 -04:00
gpsSample gps_sample_new = { } ;
2015-12-07 04:26:30 -04:00
gps_sample_new . time_us = gps - > time_usec - _params . gps_delay_ms * 1000 ;
2015-11-19 13:08:04 -04:00
2016-05-22 12:40:43 -03:00
gps_sample_new . time_us - = FILTER_UPDATE_PERIOD_MS * 1000 / 2 ;
2015-12-26 02:52:14 -04:00
_time_last_gps = time_usec ;
2015-11-19 13:08:04 -04:00
gps_sample_new . time_us = math : : max ( gps_sample_new . time_us , _imu_sample_delayed . time_us ) ;
2017-01-04 05:43:09 -04:00
memcpy ( & gps_sample_new . vel . _data [ 0 ] , gps - > vel_ned , sizeof ( gps_sample_new . vel . _data ) ) ;
2015-11-19 13:08:04 -04:00
_gps_speed_valid = gps - > vel_ned_valid ;
2016-03-15 03:07:33 -03:00
gps_sample_new . sacc = gps - > sacc ;
gps_sample_new . hacc = gps - > eph ;
gps_sample_new . vacc = gps - > epv ;
gps_sample_new . hgt = ( float ) gps - > alt * 1e-3 f ;
// Only calculate the relative position if the WGS-84 location of the origin is set
if ( collect_gps ( time_usec , gps ) ) {
float lpos_x = 0.0f ;
float lpos_y = 0.0f ;
map_projection_project ( & _pos_ref , ( gps - > lat / 1.0e7 ) , ( gps - > lon / 1.0e7 ) , & lpos_x , & lpos_y ) ;
gps_sample_new . pos ( 0 ) = lpos_x ;
gps_sample_new . pos ( 1 ) = lpos_y ;
} else {
gps_sample_new . pos ( 0 ) = 0.0f ;
gps_sample_new . pos ( 1 ) = 0.0f ;
}
2015-11-19 13:08:04 -04:00
_gps_buffer . push ( gps_sample_new ) ;
}
}
2016-01-31 03:37:34 -04:00
void EstimatorInterface : : setBaroData ( uint64_t time_usec , float * data )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
if ( ! _initialised ) {
2016-01-30 16:46:01 -04:00
return ;
}
2016-01-31 04:01:44 -04:00
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_baro > _min_obs_interval_us ) {
2015-11-19 13:08:04 -04:00
baroSample baro_sample_new ;
baro_sample_new . hgt = * data ;
baro_sample_new . time_us = time_usec - _params . baro_delay_ms * 1000 ;
2016-05-22 12:40:43 -03:00
baro_sample_new . time_us - = FILTER_UPDATE_PERIOD_MS * 1000 / 2 ;
2015-12-26 02:52:14 -04:00
_time_last_baro = time_usec ;
2015-11-19 13:08:04 -04:00
baro_sample_new . time_us = math : : max ( baro_sample_new . time_us , _imu_sample_delayed . time_us ) ;
_baro_buffer . push ( baro_sample_new ) ;
}
}
2016-04-05 10:14:04 -03:00
void EstimatorInterface : : setAirspeedData ( uint64_t time_usec , float * true_airspeed , float * eas2tas )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
if ( ! _initialised ) {
2016-01-30 16:46:01 -04:00
return ;
}
2016-01-31 04:01:44 -04:00
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_airspeed > _min_obs_interval_us ) {
2015-11-19 13:08:04 -04:00
airspeedSample airspeed_sample_new ;
2016-04-05 10:14:04 -03:00
airspeed_sample_new . true_airspeed = * true_airspeed ;
airspeed_sample_new . eas2tas = * eas2tas ;
2016-02-24 17:17:50 -04:00
airspeed_sample_new . time_us = time_usec - _params . airspeed_delay_ms * 1000 ;
2016-05-22 12:40:43 -03:00
airspeed_sample_new . time_us - = FILTER_UPDATE_PERIOD_MS * 1000 / 2 ; //typo PeRRiod
2015-12-26 02:52:14 -04:00
_time_last_airspeed = time_usec ;
2015-11-19 13:08:04 -04:00
_airspeed_buffer . push ( airspeed_sample_new ) ;
}
}
2016-03-07 05:28:45 -04:00
static float rng ;
2015-11-19 13:08:04 -04:00
// set range data
2016-01-31 03:37:34 -04:00
void EstimatorInterface : : setRangeData ( uint64_t time_usec , float * data )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
if ( ! _initialised ) {
2016-01-30 16:46:01 -04:00
return ;
}
2016-03-07 05:28:45 -04:00
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_range > _min_obs_interval_us ) {
2016-05-19 12:58:18 -03:00
rangeSample range_sample_new = { } ;
2016-03-07 05:28:45 -04:00
range_sample_new . rng = * data ;
rng = * data ;
2016-08-12 04:00:41 -03:00
range_sample_new . time_us = time_usec - _params . range_delay_ms * 1000 ;
2016-03-07 05:28:45 -04:00
_time_last_range = time_usec ;
_range_buffer . push ( range_sample_new ) ;
}
2015-11-19 13:08:04 -04:00
}
// set optical flow data
2016-03-07 05:28:45 -04:00
void EstimatorInterface : : setOpticalFlowData ( uint64_t time_usec , flow_message * flow )
2015-11-19 13:08:04 -04:00
{
2016-05-26 00:27:08 -03:00
if ( ! _initialised ) {
2016-01-30 16:46:01 -04:00
return ;
}
2016-03-07 05:28:45 -04:00
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_optflow > _min_obs_interval_us ) {
2016-03-07 05:28:45 -04:00
// check if enough integration time
float delta_time = 1e-6 f * ( float ) flow - > dt ;
bool delta_time_good = ( delta_time > = 0.05f ) ;
// check magnitude is within sensor limits
float flow_rate_magnitude ;
bool flow_magnitude_good = false ;
if ( delta_time_good ) {
flow_rate_magnitude = flow - > flowdata . norm ( ) / delta_time ;
flow_magnitude_good = ( flow_rate_magnitude < = _params . flow_rate_max ) ;
}
// check quality metric
bool flow_quality_good = ( flow - > quality > = _params . flow_qual_min ) ;
if ( delta_time_good & & flow_magnitude_good & & flow_quality_good ) {
flowSample optflow_sample_new ;
// calculate the system time-stamp for the mid point of the integration period
optflow_sample_new . time_us = time_usec - _params . flow_delay_ms * 1000 - flow - > dt / 2 ;
// copy the quality metric returned by the PX4Flow sensor
optflow_sample_new . quality = flow - > quality ;
// NOTE: the EKF uses the reverse sign convention to the flow sensor. EKF assumes positive LOS rate is produced by a RH rotation of the image about the sensor axis.
// copy the optical and gyro measured delta angles
optflow_sample_new . flowRadXY = - flow - > flowdata ;
2016-04-09 13:22:49 -03:00
optflow_sample_new . gyroXYZ = - flow - > gyrodata ;
2016-03-07 05:28:45 -04:00
// compensate for body motion to give a LOS rate
2016-04-09 13:22:49 -03:00
optflow_sample_new . flowRadXYcomp ( 0 ) = optflow_sample_new . flowRadXY ( 0 ) - optflow_sample_new . gyroXYZ ( 0 ) ;
optflow_sample_new . flowRadXYcomp ( 1 ) = optflow_sample_new . flowRadXY ( 1 ) - optflow_sample_new . gyroXYZ ( 1 ) ;
// convert integration interval to seconds
2016-03-07 05:28:45 -04:00
optflow_sample_new . dt = 1e-6 f * ( float ) flow - > dt ;
_time_last_optflow = time_usec ;
// push to buffer
_flow_buffer . push ( optflow_sample_new ) ;
}
}
2015-11-19 13:08:04 -04:00
}
2016-03-20 05:41:40 -03:00
// set attitude and position data derived from an external vision system
void EstimatorInterface : : setExtVisionData ( uint64_t time_usec , ext_vision_message * evdata )
{
if ( ! _initialised ) {
return ;
}
2016-05-26 00:27:08 -03:00
// limit data rate to prevent data being lost
if ( time_usec - _time_last_ext_vision > _min_obs_interval_us ) {
2016-03-20 05:41:40 -03:00
extVisionSample ev_sample_new ;
// calculate the system time-stamp for the mid point of the integration period
ev_sample_new . time_us = time_usec - _params . ev_delay_ms * 1000 ;
// copy required data
ev_sample_new . angErr = evdata - > angErr ;
ev_sample_new . posErr = evdata - > posErr ;
ev_sample_new . quat = evdata - > quat ;
ev_sample_new . posNED = evdata - > posNED ;
// record time for comparison next measurement
_time_last_ext_vision = time_usec ;
// push to buffer
_ext_vision_buffer . push ( ev_sample_new ) ;
}
}
2016-01-31 03:37:34 -04:00
bool EstimatorInterface : : initialise_interface ( uint64_t timestamp )
2015-11-19 13:08:04 -04:00
{
2016-11-05 09:44:45 -03:00
// find the maximum time delay required to compensate for
uint16_t max_time_delay_ms = math : : max ( _params . mag_delay_ms ,
math : : max ( _params . range_delay_ms ,
math : : max ( _params . gps_delay_ms ,
math : : max ( _params . flow_delay_ms ,
math : : max ( _params . ev_delay_ms ,
math : : max ( _params . airspeed_delay_ms , _params . baro_delay_ms ) ) ) ) ) ) ;
// calculate the IMU buffer length required to accomodate the maximum delay with some allowance for jitter
2016-11-07 07:23:12 -04:00
_imu_buffer_length = ( max_time_delay_ms / FILTER_UPDATE_PERIOD_MS ) + 1 ;
2016-11-05 09:44:45 -03:00
2016-11-06 20:50:16 -04:00
// set the observaton buffer length to handle the minimum time of arrival between observations in combination
// with the worst case delay from current time to ekf fusion time
// allow for worst case 50% extension of the ekf fusion time horizon delay due to timing jitter
uint16_t ekf_delay_ms = max_time_delay_ms + ( int ) ( ceil ( ( float ) max_time_delay_ms * 0.5f ) ) ;
2016-11-07 07:23:12 -04:00
_obs_buffer_length = ( ekf_delay_ms / _params . sensor_interval_min_ms ) + 1 ;
2016-11-06 20:50:16 -04:00
// limit to be no longer than the IMU buffer (we can't process data faster than the EKF prediction rate)
2016-11-07 07:23:12 -04:00
_obs_buffer_length = math : : min ( _obs_buffer_length , _imu_buffer_length ) ;
if ( ! ( _imu_buffer . allocate ( _imu_buffer_length ) & &
_gps_buffer . allocate ( _obs_buffer_length ) & &
_mag_buffer . allocate ( _obs_buffer_length ) & &
_baro_buffer . allocate ( _obs_buffer_length ) & &
_range_buffer . allocate ( _obs_buffer_length ) & &
_airspeed_buffer . allocate ( _obs_buffer_length ) & &
_flow_buffer . allocate ( _obs_buffer_length ) & &
_ext_vision_buffer . allocate ( _obs_buffer_length ) & &
_output_buffer . allocate ( _imu_buffer_length ) ) ) {
2016-06-02 11:58:26 -03:00
ECL_ERR ( " EKF buffer allocation failed! " ) ;
2016-01-31 03:48:41 -04:00
unallocate_buffers ( ) ;
return false ;
}
2015-11-19 13:08:04 -04:00
2016-03-20 01:13:27 -03:00
// zero the data in the observation buffers
2016-11-07 07:23:12 -04:00
for ( int index = 0 ; index < _obs_buffer_length ; index + + ) {
2016-03-20 01:13:27 -03:00
gpsSample gps_sample_init = { } ;
_gps_buffer . push ( gps_sample_init ) ;
magSample mag_sample_init = { } ;
_mag_buffer . push ( mag_sample_init ) ;
baroSample baro_sample_init = { } ;
_baro_buffer . push ( baro_sample_init ) ;
rangeSample range_sample_init = { } ;
_range_buffer . push ( range_sample_init ) ;
airspeedSample airspeed_sample_init = { } ;
_airspeed_buffer . push ( airspeed_sample_init ) ;
flowSample flow_sample_init = { } ;
_flow_buffer . push ( flow_sample_init ) ;
2016-03-20 05:41:40 -03:00
extVisionSample ext_vision_sample_init = { } ;
_ext_vision_buffer . push ( ext_vision_sample_init ) ;
2016-03-20 01:13:27 -03:00
}
// zero the data in the imu data and output observer state buffers
2016-11-07 07:23:12 -04:00
for ( int index = 0 ; index < _imu_buffer_length ; index + + ) {
2016-03-20 01:13:27 -03:00
imuSample imu_sample_init = { } ;
_imu_buffer . push ( imu_sample_init ) ;
outputSample output_sample_init = { } ;
_output_buffer . push ( output_sample_init ) ;
}
2015-11-19 13:08:04 -04:00
_dt_imu_avg = 0.0f ;
_imu_sample_delayed . delta_ang . setZero ( ) ;
_imu_sample_delayed . delta_vel . setZero ( ) ;
_imu_sample_delayed . delta_ang_dt = 0.0f ;
_imu_sample_delayed . delta_vel_dt = 0.0f ;
2016-01-30 16:42:24 -04:00
_imu_sample_delayed . time_us = timestamp ;
2015-11-19 13:08:04 -04:00
_imu_ticks = 0 ;
_initialised = false ;
2015-12-07 04:26:30 -04:00
2015-11-19 13:08:04 -04:00
_time_last_imu = 0 ;
_time_last_gps = 0 ;
_time_last_mag = 0 ;
_time_last_baro = 0 ;
_time_last_range = 0 ;
_time_last_airspeed = 0 ;
2016-03-07 05:28:45 -04:00
_time_last_optflow = 0 ;
2016-05-07 08:11:16 -03:00
memset ( & _fault_status . flags , 0 , sizeof ( _fault_status . flags ) ) ;
2016-04-19 11:36:22 -03:00
_time_last_ext_vision = 0 ;
2016-01-30 16:42:24 -04:00
return true ;
2015-11-19 13:08:04 -04:00
}
2016-01-31 03:48:41 -04:00
void EstimatorInterface : : unallocate_buffers ( )
{
_imu_buffer . unallocate ( ) ;
_gps_buffer . unallocate ( ) ;
_mag_buffer . unallocate ( ) ;
_baro_buffer . unallocate ( ) ;
_range_buffer . unallocate ( ) ;
_airspeed_buffer . unallocate ( ) ;
_flow_buffer . unallocate ( ) ;
2016-03-20 05:41:40 -03:00
_ext_vision_buffer . unallocate ( ) ;
2016-01-31 03:48:41 -04:00
_output_buffer . unallocate ( ) ;
}
2016-03-07 05:28:45 -04:00
bool EstimatorInterface : : local_position_is_valid ( )
2015-12-31 20:56:38 -04:00
{
// return true if the position estimate is valid
2016-05-18 01:07:04 -03:00
return ( ( ( _time_last_imu - _time_last_optflow ) < 5e6 ) & & _control_status . flags . opt_flow ) | |
( ( ( _time_last_imu - _time_last_ext_vision ) < 5e6 ) & & _control_status . flags . ev_pos ) | |
global_position_is_valid ( ) ;
2015-12-31 20:56:38 -04:00
}