2013-05-19 17:11:09 +02:00
/**
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * *
* @ addtogroup OpenPilotModules OpenPilot Modules
* @ {
* @ addtogroup State Estimation
* @ brief Acquires sensor data and computes state estimate
* @ {
*
* @ file stateestimation . c
* @ author The OpenPilot Team , http : //www.openpilot.org Copyright (C) 2013.
* @ brief Module to handle all comms to the AHRS on a periodic basis .
*
* @ see The GNU Public License ( GPL ) Version 3
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/*
* 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 , write to the Free Software Foundation , Inc . ,
* 59 Temple Place , Suite 330 , Boston , MA 02111 - 1307 USA
*/
2013-05-19 21:44:33 +02:00
# include "inc/stateestimation.h"
2013-05-19 20:38:32 +02:00
2013-05-19 17:11:09 +02:00
# include <gyrosensor.h>
# include <accelsensor.h>
2013-05-20 10:35:54 +02:00
# include <magsensor.h>
2013-05-19 17:11:09 +02:00
# include <barosensor.h>
# include <airspeedsensor.h>
# include <gpsposition.h>
# include <gpsvelocity.h>
2013-05-19 20:38:32 +02:00
# include <gyrostate.h>
# include <accelstate.h>
2013-05-20 10:35:54 +02:00
# include <magstate.h>
2013-05-19 20:38:32 +02:00
# include <barostate.h>
# include <airspeedstate.h>
2013-05-20 10:42:23 +02:00
# include <attitudestate.h>
2013-05-19 20:38:32 +02:00
# include <positionstate.h>
# include <velocitystate.h>
2013-05-19 17:11:09 +02:00
# include "revosettings.h"
# include "homelocation.h"
2013-05-19 20:38:32 +02:00
# include "flightstatus.h"
2013-05-19 17:11:09 +02:00
2013-05-20 10:42:23 +02:00
# include "CoordinateConversions.h"
2013-05-19 17:11:09 +02:00
// Private constants
# define STACK_SIZE_BYTES 2048
2013-05-19 21:44:33 +02:00
# define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
# define TASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
2013-05-19 17:11:09 +02:00
# define TIMEOUT_MS 100
// Private types
2013-05-19 21:44:33 +02:00
struct filterQueueStruct ;
typedef struct filterQueueStruct {
stateFilter * filter ;
struct filterQueueStruct * next ;
} filterQueue ;
2013-05-19 17:11:09 +02:00
// Private variables
static DelayedCallbackInfo * stateEstimationCallback ;
2013-05-19 20:38:32 +02:00
static volatile RevoSettingsData revoSettings ;
static volatile HomeLocationData homeLocation ;
2013-05-19 17:11:09 +02:00
static float LLA2NEDM [ 3 ] ;
static volatile sensorUpdates updatedSensors ;
2013-05-19 20:38:32 +02:00
static int32_t fusionAlgorithm = - 1 ;
static filterQueue * filterChain = NULL ;
// different filters available to state estimation
2013-05-19 21:44:33 +02:00
static stateFilter magFilter ;
static stateFilter baroFilter ;
static stateFilter airFilter ;
static stateFilter stationaryFilter ;
static stateFilter cfFilter ;
static stateFilter cfmFilter ;
static stateFilter ekf13iFilter ;
static stateFilter ekf13Filter ;
static stateFilter ekf16Filter ;
static stateFilter ekf16iFilter ;
2013-05-19 20:38:32 +02:00
// preconfigured filter chains selectable via revoSettings.FusionAlgorithm
static const filterQueue * cfQueue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & cfFilter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
2013-05-19 21:44:33 +02:00
} ,
2013-05-19 20:38:32 +02:00
}
}
} ;
static const filterQueue * cfmQueue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & cfmFilter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
}
}
}
} ;
static const filterQueue * ekf13iQueue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & stationaryFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & ekf13iFilter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
}
}
}
}
} ;
static const filterQueue * ekf13Queue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & ekf13Filter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
}
}
}
} ;
static const filterQueue * ekf16iQueue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & stationaryFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & ekf16iFilter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
}
}
}
}
} ;
static const filterQueue * ekf16Queue = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & magFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & airFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-20 12:36:20 +02:00
. filter = & baroFilter ,
2013-05-19 20:38:32 +02:00
. next = & ( filterQueue ) {
2013-05-19 21:44:33 +02:00
. filter = & ekf16Filter ,
2013-05-19 20:38:32 +02:00
. next = NULL ,
}
}
}
} ;
2013-05-19 17:11:09 +02:00
// Private functions
static void settingsUpdatedCb ( UAVObjEvent * objEv ) ;
static void sensorUpdatedCb ( UAVObjEvent * objEv ) ;
static void StateEstimationCb ( void ) ;
2013-05-19 20:38:32 +02:00
static void getNED ( GPSPositionData * gpsPosition , float * NED ) ;
2013-05-19 21:44:33 +02:00
static float sane ( float value ) ;
2013-05-19 17:11:09 +02:00
/**
* Initialise the module . Called before the start function
* \ returns 0 on success or - 1 if initialisation failed
*/
int32_t StateEstimationInitialize ( void )
{
RevoSettingsInitialize ( ) ;
RevoSettingsConnectCallback ( & settingsUpdatedCb ) ;
HomeLocationConnectCallback ( & settingsUpdatedCb ) ;
GyroSensorConnectCallback ( & sensorUpdatedCb ) ;
AccelSensorConnectCallback ( & sensorUpdatedCb ) ;
2013-05-20 10:35:54 +02:00
MagSensorConnectCallback ( & sensorUpdatedCb ) ;
2013-05-19 17:11:09 +02:00
BaroSensorConnectCallback ( & sensorUpdatedCb ) ;
AirspeedSensorConnectCallback ( & sensorUpdatedCb ) ;
GPSPositionConnectCallback ( & sensorUpdatedCb ) ;
GPSVelocityConnectCallback ( & sensorUpdatedCb ) ;
stateEstimationCallback = DelayedCallbackCreate ( & StateEstimationCb , CALLBACK_PRIORITY , TASK_PRIORITY , STACK_SIZE_BYTES ) ;
return 0 ;
}
/**
* Start the task . Expects all objects to be initialized by this point .
* \ returns 0 on success or - 1 if initialisation failed
*/
int32_t StateEstimationStart ( void )
{
RevoSettingsConnectCallback ( & settingsUpdatedCb ) ;
// Force settings update to make sure rotation loaded
settingsUpdatedCb ( NULL ) ;
// Initialize Filters
2013-05-19 21:44:33 +02:00
filterMagInitialize ( & magFilter ) ;
filterBaroInitialize ( & baroFilter ) ;
filterAirInitialize ( & airFilter ) ;
filterStationaryInitialize ( & stationaryFilter ) ;
filterCFInitialize ( & cfFilter ) ;
filterCFMInitialize ( & cfmFilter ) ;
filterEKF13iInitialize ( & ekf13iFilter ) ;
filterEKF13Initialize ( & ekf13Filter ) ;
filterEKF16Initialize ( & ekf16Filter ) ;
filterEKF16iInitialize ( & ekf16iFilter ) ;
2013-05-19 17:11:09 +02:00
return 0 ;
}
MODULE_INITCALL ( AttitudeInitialize , AttitudeStart )
/**
* Module callback
*/
static void StateEstimationCb ( void )
{
// alarms flag
uint8_t alarm = 0 ;
// set alarm to warning if called through timeout
2013-05-19 21:44:33 +02:00
if ( updatedSensors = = 0 ) {
2013-05-19 17:11:09 +02:00
AlarmsSet ( SYSTEMALARMS_ALARM_ATTITUDE , SYSTEMALARMS_ALARM_WARNING ) ;
alarm = 1 ;
}
2013-05-19 20:38:32 +02:00
// check if a new filter chain should be initialized
2013-05-19 21:44:33 +02:00
if ( fusionAlgorithm ! = revoSettings . FusionAlgorithm ) {
2013-05-19 20:38:32 +02:00
FlightStatusData fs ;
FlightStatusGet ( & fs ) ;
if ( fs . Armed = = FLIGHTSTATUS_ARMED_DISARMED | | fusionAlgorithm = = - 1 ) {
2013-05-19 21:44:33 +02:00
const filterQueue * newFilterChain ;
switch ( revoSettings . FusionAlgorithm ) {
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARY :
2013-05-19 20:38:32 +02:00
newFilterChain = cfQueue ;
break ;
2013-05-19 21:44:33 +02:00
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAG :
2013-05-19 20:38:32 +02:00
newFilterChain = cfmQueue ;
break ;
2013-05-19 21:44:33 +02:00
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR :
2013-05-19 20:38:32 +02:00
newFilterChain = ekf13iQueue ;
break ;
2013-05-19 21:44:33 +02:00
case REVOSETTINGS_FUSIONALGORITHM_INS13OUTDOOR :
2013-05-19 20:38:32 +02:00
newFilterChain = ekf13Queue ;
break ;
2013-05-19 21:44:33 +02:00
case REVOSETTINGS_FUSIONALGORITHM_INS16INDOOR :
2013-05-19 20:38:32 +02:00
newFilterChain = ekf16iQueue ;
break ;
2013-05-19 21:44:33 +02:00
case REVOSETTINGS_FUSIONALGORITHM_INS16OUTDOOR :
2013-05-19 20:38:32 +02:00
newFilterChain = ekf16Queue ;
break ;
default :
newFilterChain = NULL ;
}
// initialize filters in chain
2013-05-19 21:44:33 +02:00
filterQueue * current = ( filterQueue * ) newFilterChain ;
2013-05-19 20:38:32 +02:00
bool error = 0 ;
while ( current ! = NULL ) {
2013-05-19 21:44:33 +02:00
int32_t result = current - > filter - > init ( ) ;
2013-05-19 20:38:32 +02:00
if ( result ! = 0 ) {
error = 1 ;
break ;
}
2013-05-19 21:44:33 +02:00
current = current - > next ;
2013-05-19 20:38:32 +02:00
}
if ( error ) {
AlarmsSet ( SYSTEMALARMS_ALARM_ATTITUDE , SYSTEMALARMS_ALARM_ERROR ) ;
return ;
} else {
// set new fusion algortithm
2013-05-19 21:44:33 +02:00
filterChain = ( filterQueue * ) newFilterChain ;
fusionAlgorithm = revoSettings . FusionAlgorithm ;
2013-05-19 20:38:32 +02:00
}
}
}
2013-05-19 17:11:09 +02:00
// read updated sensor UAVObjects and set initial state
2013-05-19 20:38:32 +02:00
stateEstimation states ;
states . updated = updatedSensors ;
updatedSensors ^ = states . updated ;
2013-05-19 17:11:09 +02:00
// most sensors get only rudimentary sanity checks
2013-05-19 20:38:32 +02:00
# define SANITYCHECK3(sensorname, shortname, a1, a2, a3) \
if ( ISSET ( states . updated , shortname # # _UPDATED ) ) { \
2013-05-19 17:11:09 +02:00
sensorname # # Data s ; \
2013-05-19 21:44:33 +02:00
sensorname # # Get ( & s ) ; \
2013-05-19 17:11:09 +02:00
if ( sane ( s . a1 ) & & sane ( s . a2 ) & & sane ( s . a3 ) ) { \
2013-05-19 20:38:32 +02:00
states . shortname [ 0 ] = s . a1 ; \
states . shortname [ 1 ] = s . a2 ; \
states . shortname [ 2 ] = s . a3 ; \
2013-05-19 17:11:09 +02:00
} \
else { \
2013-05-19 20:38:32 +02:00
UNSET ( states . updated , shortname # # _UPDATED ) ; \
2013-05-19 17:11:09 +02:00
} \
}
SANITYCHECK3 ( GyroSensor , gyr , x , y , z ) ;
SANITYCHECK3 ( AccelSensor , acc , x , y , z ) ;
2013-05-20 10:35:54 +02:00
SANITYCHECK3 ( MagSensor , mag , x , y , z ) ;
2013-05-19 17:11:09 +02:00
SANITYCHECK3 ( GPSVelocity , vel , North , East , Down ) ;
2013-05-19 20:38:32 +02:00
# define SANITYCHECK1(sensorname, shortname, a1, EXTRACHECK) \
if ( ISSET ( states . updated , shortname # # _UPDATED ) ) { \
2013-05-19 17:11:09 +02:00
sensorname # # Data s ; \
2013-05-19 21:44:33 +02:00
sensorname # # Get ( & s ) ; \
2013-05-19 17:11:09 +02:00
if ( sane ( s . a1 ) & & EXTRACHECK ) { \
2013-05-19 20:38:32 +02:00
states . shortname [ 0 ] = s . a1 ; \
2013-05-19 17:11:09 +02:00
} \
else { \
2013-05-19 20:38:32 +02:00
UNSET ( states . updated , shortname # # _UPDATED ) ; \
2013-05-19 17:11:09 +02:00
} \
}
SANITYCHECK1 ( BaroSensor , bar , Altitude , 1 ) ;
2013-05-19 20:38:32 +02:00
SANITYCHECK1 ( AirspeedSensor , air , CalibratedAirspeed , s . SensorConnected = = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE ) ;
2013-05-20 12:36:20 +02:00
states . air [ 1 ] = 0.0f ; // sensor does not provide true airspeed, needs to be calculated by filter
2013-05-19 17:11:09 +02:00
2013-05-19 20:38:32 +02:00
// GPS is a tiny bit more tricky as GPSPosition is not float (otherwise the conversion to NED could sit in a filter) but integers, for precision reasons
if ( ISSET ( states . updated , pos_UPDATED ) ) {
2013-05-19 17:11:09 +02:00
GPSPositionData s ;
GPSPositionGet ( & s ) ;
if ( homeLocation . Set = = HOMELOCATION_SET_TRUE & & sane ( s . Latitude ) & & sane ( s . Longitude ) & & sane ( s . Altitude ) & & ( fabsf ( s . Latitude ) > 1e-5 f | | fabsf ( s . Latitude ) > 1e-5 f | | fabsf ( s . Latitude ) > 1e-5 f ) ) {
2013-05-19 20:38:32 +02:00
getNED ( & s , states . pos ) ;
2013-05-19 17:11:09 +02:00
} else {
2013-05-19 20:38:32 +02:00
UNSET ( states . updated , pos_UPDATED ) ;
2013-05-19 17:11:09 +02:00
}
}
2013-05-19 20:38:32 +02:00
// at this point sensor state is stored in "states" with some rudimentary filtering applied
2013-05-19 17:11:09 +02:00
2013-05-19 20:38:32 +02:00
// apply all filters in the current filter chain
2013-05-19 21:44:33 +02:00
filterQueue * current = ( filterQueue * ) filterChain ;
2013-05-19 20:38:32 +02:00
bool error = 0 ;
while ( current ! = NULL ) {
2013-05-19 21:44:33 +02:00
int32_t result = current - > filter - > filter ( & states ) ;
2013-05-19 20:38:32 +02:00
if ( result ! = 0 ) {
error = 1 ;
}
2013-05-19 21:44:33 +02:00
current = current - > next ;
2013-05-19 20:38:32 +02:00
}
if ( error ) {
AlarmsSet ( SYSTEMALARMS_ALARM_ATTITUDE , SYSTEMALARMS_ALARM_ERROR ) ;
}
// the final output of filters is saved in state variables
# define STORE3(statename, shortname, a1, a2, a3) \
if ( ISSET ( states . updated , shortname # # _UPDATED ) ) { \
statename # # Data s ; \
2013-05-19 21:44:33 +02:00
statename # # Get ( & s ) ; \
2013-05-19 20:38:32 +02:00
s . a1 = states . shortname [ 0 ] ; \
s . a2 = states . shortname [ 1 ] ; \
s . a3 = states . shortname [ 2 ] ; \
2013-05-19 21:44:33 +02:00
statename # # Set ( & s ) ; \
2013-05-19 20:38:32 +02:00
}
STORE3 ( GyroState , gyr , x , y , z ) ;
STORE3 ( AccelState , acc , x , y , z ) ;
2013-05-20 10:35:54 +02:00
STORE3 ( MagState , mag , x , y , z ) ;
2013-05-19 20:38:32 +02:00
STORE3 ( PositionState , pos , North , East , Down ) ;
STORE3 ( VelocityState , vel , North , East , Down ) ;
# define STORE2(statename, shortname, a1, a2) \
if ( ISSET ( states . updated , shortname # # _UPDATED ) ) { \
statename # # Data s ; \
2013-05-19 21:44:33 +02:00
statename # # Get ( & s ) ; \
2013-05-19 20:38:32 +02:00
s . a1 = states . shortname [ 0 ] ; \
s . a2 = states . shortname [ 1 ] ; \
2013-05-19 21:44:33 +02:00
statename # # Set ( & s ) ; \
2013-05-19 20:38:32 +02:00
}
STORE2 ( AirspeedState , air , CalibratedAirspeed , TrueAirspeed ) ;
# define STORE1(statename, shortname, a1) \
if ( ISSET ( states . updated , shortname # # _UPDATED ) ) { \
statename # # Data s ; \
2013-05-19 21:44:33 +02:00
statename # # Get ( & s ) ; \
2013-05-19 20:38:32 +02:00
s . a1 = states . shortname [ 0 ] ; \
2013-05-19 21:44:33 +02:00
statename # # Set ( & s ) ; \
2013-05-19 20:38:32 +02:00
}
STORE1 ( BaroState , bar , Altitude ) ;
2013-05-20 10:42:23 +02:00
// attitude nees manual conversion from quaternion to euler
if ( ISSET ( states . updated , att_UPDATED ) ) { \
AttitudeStateData s ;
AttitudeStateGet ( & s ) ;
s . q1 = states . att [ 0 ] ;
s . q2 = states . att [ 1 ] ;
s . q3 = states . att [ 2 ] ;
s . q4 = states . att [ 3 ] ;
Quaternion2RPY ( & s . q1 , & s . Roll ) ;
AttitudeStateSet ( & s ) ;
}
2013-05-19 17:11:09 +02:00
// clear alarms if everything is alright, then schedule callback execution after timeout
if ( ! alarm ) {
AlarmsClear ( SYSTEMALARMS_ALARM_ATTITUDE ) ;
}
2013-05-19 21:44:33 +02:00
DelayedCallbackSchedule ( stateEstimationCallback , TIMEOUT_MS , CALLBACK_UPDATEMODE_SOONER ) ;
2013-05-19 17:11:09 +02:00
}
2013-05-19 21:44:33 +02:00
/**
* Callback for eventdispatcher when HomeLocation or RevoSettings has been updated
*/
2013-05-19 17:11:09 +02:00
static void settingsUpdatedCb ( UAVObjEvent * ev )
{
2013-05-19 21:44:33 +02:00
HomeLocationGet ( ( HomeLocationData * ) & homeLocation ) ;
2013-05-19 17:11:09 +02:00
if ( sane ( homeLocation . Latitude ) & & sane ( homeLocation . Longitude ) & & sane ( homeLocation . Altitude ) & & sane ( homeLocation . Be [ 0 ] ) & & sane ( homeLocation . Be [ 1 ] ) & & sane ( homeLocation . Be [ 2 ] ) ) {
// Compute matrix to convert deltaLLA to NED
float lat , alt ;
lat = DEG2RAD ( homeLocation . Latitude / 10.0e6 f ) ;
alt = homeLocation . Altitude ;
LLA2NEDM [ 0 ] = alt + 6.378137E6 f ;
LLA2NEDM [ 1 ] = cosf ( lat ) * ( alt + 6.378137E6 f ) ;
LLA2NEDM [ 2 ] = - 1.0f ;
// TODO: convert positionState to new reference frame and gracefully update EKF state!
// needed for long range flights where the reference coordinate is adjusted in flight
}
2013-05-19 21:44:33 +02:00
RevoSettingsGet ( ( RevoSettingsData * ) & revoSettings ) ;
2013-05-19 17:11:09 +02:00
}
2013-05-19 21:44:33 +02:00
/**
* Callback for eventdispatcher when any sensor UAVObject has been updated
* updates the list of " recently updated UAVObjects " and dispatches the state estimator callback
*/
2013-05-19 17:11:09 +02:00
static void sensorUpdatedCb ( UAVObjEvent * ev )
{
if ( ! ev ) {
return ;
}
if ( ev - > obj = = GyroSensorHandle ( ) ) {
updatedSensors | = gyr_UPDATED ;
}
if ( ev - > obj = = AccelSensorHandle ( ) ) {
updatedSensors | = acc_UPDATED ;
}
2013-05-20 10:35:54 +02:00
if ( ev - > obj = = MagSensorHandle ( ) ) {
2013-05-19 17:11:09 +02:00
updatedSensors | = mag_UPDATED ;
}
if ( ev - > obj = = GPSPositionHandle ( ) ) {
updatedSensors | = pos_UPDATED ;
}
if ( ev - > obj = = GPSVelocityHandle ( ) ) {
updatedSensors | = vel_UPDATED ;
}
if ( ev - > obj = = BaroSensorHandle ( ) ) {
updatedSensors | = bar_UPDATED ;
}
if ( ev - > obj = = AirspeedSensorHandle ( ) ) {
2013-05-19 20:38:32 +02:00
updatedSensors | = air_UPDATED ;
2013-05-19 17:11:09 +02:00
}
DelayedCallbackDispatch ( stateEstimationCallback ) ;
}
/**
* @ brief Convert the GPS LLA position into NED coordinates
* @ note this method uses a taylor expansion around the home coordinates
* to convert to NED which allows it to be done with all floating
* calculations
* @ param [ in ] Current GPS coordinates
* @ param [ out ] NED frame coordinates
* @ returns 0 for success , - 1 for failure
*/
static void getNED ( GPSPositionData * gpsPosition , float * NED )
{
float dL [ 3 ] = { DEG2RAD ( ( gpsPosition - > Latitude - homeLocation . Latitude ) / 10.0e6 f ) ,
DEG2RAD ( ( gpsPosition - > Longitude - homeLocation . Longitude ) / 10.0e6 f ) ,
( gpsPosition - > Altitude + gpsPosition - > GeoidSeparation - homeLocation . Altitude ) } ;
NED [ 0 ] = LLA2NEDM [ 0 ] * dL [ 0 ] ;
NED [ 1 ] = LLA2NEDM [ 1 ] * dL [ 1 ] ;
NED [ 2 ] = LLA2NEDM [ 2 ] * dL [ 2 ] ;
}
2013-05-19 21:44:33 +02:00
/**
* @ brief sanity check for float values
* @ note makes sure a float value is safe for further processing , ie not NAN and not INF
* @ param [ in ] float value
* @ returns true for safe and false for unsafe
*/
static float sane ( float value )
{
if ( isnan ( value ) | | isinf ( value ) ) {
return false ;
}
return true ;
}
2013-05-19 17:11:09 +02:00
/**
* @ }
* @ }
*/