2019-07-03 00:58:36 -03:00
# include "AP_NavEKF2.h"
2020-11-24 01:44:09 -04:00
# include "AP_NavEKF2_core.h"
2019-07-03 00:58:36 -03:00
# include <AP_Logger/AP_Logger.h>
2020-11-05 19:30:16 -04:00
# include <AP_DAL/AP_DAL.h>
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_NKF1 ( uint64_t time_us ) const
2019-07-03 00:58:36 -03:00
{
// Write first EKF packet
Vector3f euler ;
Vector2f posNE ;
float posD ;
Vector3f velNED ;
Vector3f gyroBias ;
float posDownDeriv ;
Location originLLH ;
2020-11-24 01:44:09 -04:00
getEulerAngles ( euler ) ;
getVelNED ( velNED ) ;
getPosNE ( posNE ) ;
getPosD ( posD ) ;
getGyroBias ( gyroBias ) ;
posDownDeriv = getPosDownDerivative ( ) ;
if ( ! getOriginLLH ( originLLH ) ) {
2019-07-03 00:58:36 -03:00
originLLH . alt = 0 ;
}
2020-12-03 06:28:18 -04:00
const struct log_NKF1 pkt {
2019-12-06 03:14:10 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKF1_MSG ) ,
2019-07-03 00:58:36 -03:00
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-03 00:58:36 -03:00
roll : ( int16_t ) ( 100 * degrees ( euler . x ) ) , // roll angle (centi-deg, displayed as deg due to format string)
pitch : ( int16_t ) ( 100 * degrees ( euler . y ) ) , // pitch angle (centi-deg, displayed as deg due to format string)
yaw : ( uint16_t ) wrap_360_cd ( 100 * degrees ( euler . z ) ) , // yaw angle (centi-deg, displayed as deg due to format string)
velN : ( float ) ( velNED . x ) , // velocity North (m/s)
velE : ( float ) ( velNED . y ) , // velocity East (m/s)
velD : ( float ) ( velNED . z ) , // velocity Down (m/s)
posD_dot : ( float ) ( posDownDeriv ) , // first derivative of down position
posN : ( float ) ( posNE . x ) , // metres North
posE : ( float ) ( posNE . y ) , // metres East
posD : ( float ) ( posD ) , // metres Down
gyrX : ( int16_t ) ( 100 * degrees ( gyroBias . x ) ) , // cd/sec, displayed as deg/sec due to format string
gyrY : ( int16_t ) ( 100 * degrees ( gyroBias . y ) ) , // cd/sec, displayed as deg/sec due to format string
gyrZ : ( int16_t ) ( 100 * degrees ( gyroBias . z ) ) , // cd/sec, displayed as deg/sec due to format string
originHgt : originLLH . alt // WGS-84 altitude of EKF origin in cm
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pkt , sizeof ( pkt ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_NKF2 ( uint64_t time_us ) const
2019-07-02 21:31:19 -03:00
{
2019-07-03 00:58:36 -03:00
// Write second EKF packet
float azbias = 0 ;
Vector3f wind ;
Vector3f magNED ;
Vector3f magXYZ ;
Vector3f gyroScaleFactor ;
2020-11-24 01:44:09 -04:00
getAccelZBias ( azbias ) ;
getWind ( wind ) ;
getMagNED ( magNED ) ;
getMagXYZ ( magXYZ ) ;
getGyroScaleErrorPercentage ( gyroScaleFactor ) ;
2019-07-02 21:31:19 -03:00
const struct log_NKF2 pkt2 {
2019-12-06 03:14:10 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKF2_MSG ) ,
2019-07-03 00:58:36 -03:00
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-03 00:58:36 -03:00
AZbias : ( int8_t ) ( 100 * azbias ) ,
scaleX : ( int16_t ) ( 100 * gyroScaleFactor . x ) ,
scaleY : ( int16_t ) ( 100 * gyroScaleFactor . y ) ,
scaleZ : ( int16_t ) ( 100 * gyroScaleFactor . z ) ,
windN : ( int16_t ) ( 100 * wind . x ) ,
windE : ( int16_t ) ( 100 * wind . y ) ,
magN : ( int16_t ) ( magNED . x ) ,
magE : ( int16_t ) ( magNED . y ) ,
magD : ( int16_t ) ( magNED . z ) ,
magX : ( int16_t ) ( magXYZ . x ) ,
magY : ( int16_t ) ( magXYZ . y ) ,
magZ : ( int16_t ) ( magXYZ . z ) ,
2020-11-24 01:44:09 -04:00
index : magSelectIndex
2019-07-03 00:58:36 -03:00
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pkt2 , sizeof ( pkt2 ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_NKF3 ( uint64_t time_us ) const
2019-07-02 21:31:19 -03:00
{
2019-07-03 00:58:36 -03:00
// Write third EKF packet
Vector3f velInnov ;
Vector3f posInnov ;
Vector3f magInnov ;
float tasInnov = 0 ;
float yawInnov = 0 ;
2020-11-24 01:44:09 -04:00
getInnovations ( velInnov , posInnov , magInnov , tasInnov , yawInnov ) ;
2019-07-02 21:31:19 -03:00
const struct log_NKF3 pkt3 {
2019-12-06 03:14:10 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKF3_MSG ) ,
2019-07-03 00:58:36 -03:00
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-03 00:58:36 -03:00
innovVN : ( int16_t ) ( 100 * velInnov . x ) ,
innovVE : ( int16_t ) ( 100 * velInnov . y ) ,
innovVD : ( int16_t ) ( 100 * velInnov . z ) ,
innovPN : ( int16_t ) ( 100 * posInnov . x ) ,
innovPE : ( int16_t ) ( 100 * posInnov . y ) ,
innovPD : ( int16_t ) ( 100 * posInnov . z ) ,
innovMX : ( int16_t ) ( magInnov . x ) ,
innovMY : ( int16_t ) ( magInnov . y ) ,
innovMZ : ( int16_t ) ( magInnov . z ) ,
innovYaw : ( int16_t ) ( 100 * degrees ( yawInnov ) ) ,
2020-06-19 10:16:53 -03:00
innovVT : ( int16_t ) ( 100 * tasInnov ) ,
rerr : 0 , // TODO : Relative Error based Lane-Switching like EK3
errorScore : 0 // TODO : Relative Error based Lane-Switching like EK3
2019-07-03 00:58:36 -03:00
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pkt3 , sizeof ( pkt3 ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_NKF4 ( uint64_t time_us ) const
2019-07-02 21:31:19 -03:00
{
2019-07-03 00:58:36 -03:00
// Write fourth EKF packet
float velVar = 0 ;
float posVar = 0 ;
float hgtVar = 0 ;
Vector3f magVar ;
float tasVar = 0 ;
Vector2f offset ;
2020-11-24 01:44:09 -04:00
uint16_t _faultStatus = 0 ;
2021-01-21 03:02:07 -04:00
const uint8_t timeoutStatus =
posTimeout < < 0 |
velTimeout < < 1 |
hgtTimeout < < 2 |
magTimeout < < 3 |
tasTimeout < < 4 ;
2019-07-03 00:58:36 -03:00
nav_filter_status solutionStatus { } ;
nav_gps_status gpsStatus { } ;
2020-11-24 01:44:09 -04:00
getVariances ( velVar , posVar , hgtVar , magVar , tasVar , offset ) ;
2021-05-04 08:12:23 -03:00
ftype tempVar = fmaxF ( fmaxF ( magVar . x , magVar . y ) , magVar . z ) ;
2020-11-24 01:44:09 -04:00
getFilterFaults ( _faultStatus ) ;
getFilterStatus ( solutionStatus ) ;
getFilterGpsStatus ( gpsStatus ) ;
2019-07-02 21:31:19 -03:00
const struct log_NKF4 pkt4 {
2019-12-06 03:14:10 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKF4_MSG ) ,
2019-07-03 00:58:36 -03:00
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-03 00:58:36 -03:00
sqrtvarV : ( int16_t ) ( 100 * velVar ) ,
sqrtvarP : ( int16_t ) ( 100 * posVar ) ,
sqrtvarH : ( int16_t ) ( 100 * hgtVar ) ,
sqrtvarM : ( int16_t ) ( 100 * tempVar ) ,
sqrtvarVT : ( int16_t ) ( 100 * tasVar ) ,
2021-05-04 08:12:23 -03:00
tiltErr : float ( tiltErrFilt ) , // tilt error convergence metric
2021-02-27 08:41:07 -04:00
offsetNorth : offset . x ,
offsetEast : offset . y ,
2020-11-24 01:44:09 -04:00
faults : _faultStatus ,
2019-07-03 00:58:36 -03:00
timeouts : ( uint8_t ) ( timeoutStatus ) ,
2020-02-07 16:33:40 -04:00
solution : ( uint32_t ) ( solutionStatus . value ) ,
2019-07-03 00:58:36 -03:00
gps : ( uint16_t ) ( gpsStatus . value ) ,
2020-11-24 01:44:09 -04:00
primary : frontend - > getPrimaryCoreIndex ( )
2019-07-03 00:58:36 -03:00
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pkt4 , sizeof ( pkt4 ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_NKF5 ( uint64_t time_us ) const
2019-07-02 21:31:19 -03:00
{
2020-11-24 01:44:09 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
// Write fifth EKF packet
2019-07-02 21:31:19 -03:00
const struct log_NKF5 pkt5 {
2019-07-03 00:58:36 -03:00
LOG_PACKET_HEADER_INIT ( LOG_NKF5_MSG ) ,
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
normInnov : ( uint8_t ) ( MIN ( 100 * MAX ( flowTestRatio [ 0 ] , flowTestRatio [ 1 ] ) , 255 ) ) , // normalised innovation variance ratio for optical flow observations fused by the main nav filter
FIX : ( int16_t ) ( 1000 * innovOptFlow [ 0 ] ) , // optical flow LOS rate vector innovations from the main nav filter
FIY : ( int16_t ) ( 1000 * innovOptFlow [ 1 ] ) , // optical flow LOS rate vector innovations from the main nav filter
2021-09-11 07:33:42 -03:00
AFI : ( int16_t ) ( 1000 * auxFlowObsInnov . length ( ) ) , // optical flow LOS rate innovation from terrain offset estimator
2022-07-10 20:17:47 -03:00
HAGL : float_to_int16 ( 100 * ( terrainState - stateStruct . position . z ) ) , // height above ground level
2020-11-24 01:44:09 -04:00
offset : ( int16_t ) ( 100 * terrainState ) , // // estimated vertical position of the terrain relative to the nav filter zero datum
RI : ( int16_t ) ( 100 * innovRng ) , // range finder innovations
meaRng : ( uint16_t ) ( 100 * rangeDataDelayed . rng ) , // measured range
2021-05-04 08:12:23 -03:00
errHAGL : ( uint16_t ) ( 100 * sqrtF ( Popt ) ) , // filter ground offset state error
angErr : float ( outputTrackError . x ) ,
velErr : float ( outputTrackError . y ) ,
posErr : float ( outputTrackError . z )
2020-11-24 01:44:09 -04:00
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pkt5 , sizeof ( pkt5 ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_Quaternion ( uint64_t time_us ) const
2019-07-02 21:31:19 -03:00
{
2019-07-03 00:58:36 -03:00
// log quaternion
Quaternion quat ;
2020-11-24 01:44:09 -04:00
getQuaternion ( quat ) ;
2020-12-03 06:28:18 -04:00
const struct log_NKQ pktq1 {
2019-12-06 03:14:10 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKQ_MSG ) ,
2019-07-03 00:58:36 -03:00
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-03 00:58:36 -03:00
q1 : quat . q1 ,
q2 : quat . q2 ,
q3 : quat . q3 ,
q4 : quat . q4
} ;
2019-07-02 21:31:19 -03:00
AP : : logger ( ) . WriteBlock ( & pktq1 , sizeof ( pktq1 ) ) ;
}
2019-07-03 00:58:36 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_Beacon ( uint64_t time_us )
2019-07-02 21:31:19 -03:00
{
2020-11-24 01:44:09 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
2020-11-24 01:44:09 -04:00
if ( AP : : beacon ( ) = = nullptr ) {
return ;
}
if ( ! statesInitialised | | N_beacons = = 0 ) {
return ;
}
// Ensure that beacons are not skipped due to calling this
// function at a rate lower than the updates
if ( rngBcnFuseDataReportIndex > = N_beacons ) {
rngBcnFuseDataReportIndex = 0 ;
}
const rngBcnFusionReport_t & report = rngBcnFusionReport [ rngBcnFuseDataReportIndex ] ;
if ( report . rng < = 0.0f ) {
rngBcnFuseDataReportIndex + + ;
return ;
2019-07-03 00:58:36 -03:00
}
2020-11-24 01:44:09 -04:00
2020-12-03 06:28:18 -04:00
struct log_NKF0 pkt0 = {
2020-12-03 06:29:50 -04:00
LOG_PACKET_HEADER_INIT ( LOG_NKF0_MSG ) ,
2020-11-24 01:44:09 -04:00
time_us : time_us ,
core : DAL_CORE ( core_index ) ,
ID : rngBcnFuseDataReportIndex ,
rng : ( int16_t ) ( 100 * report . rng ) ,
innov : ( int16_t ) ( 100 * report . innov ) ,
sqrtInnovVar : ( uint16_t ) ( 100 * safe_sqrt ( report . innovVar ) ) ,
2021-05-04 08:12:23 -03:00
testRatio : ( uint16_t ) ( 100 * constrain_ftype ( report . testRatio , 0.0f , 650.0f ) ) ,
2020-11-24 01:44:09 -04:00
beaconPosN : ( int16_t ) ( 100 * report . beaconPosNED . x ) ,
beaconPosE : ( int16_t ) ( 100 * report . beaconPosNED . y ) ,
beaconPosD : ( int16_t ) ( 100 * report . beaconPosNED . z ) ,
offsetHigh : ( int16_t ) ( 100 * bcnPosOffsetMax ) ,
offsetLow : ( int16_t ) ( 100 * bcnPosOffsetMin ) ,
posN : 0 ,
posE : 0 ,
posD : 0
} ;
2020-12-03 06:28:18 -04:00
AP : : logger ( ) . WriteBlock ( & pkt0 , sizeof ( pkt0 ) ) ;
2020-11-24 01:44:09 -04:00
rngBcnFuseDataReportIndex + + ;
2019-07-02 21:31:19 -03:00
}
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write_Timing ( uint64_t time_us )
2020-11-05 19:30:16 -04:00
{
// log EKF timing statistics every 5s
if ( AP : : dal ( ) . millis ( ) - lastTimingLogTime_ms < = 5000 ) {
return ;
}
lastTimingLogTime_ms = AP : : dal ( ) . millis ( ) ;
const struct log_NKT nkt {
LOG_PACKET_HEADER_INIT ( LOG_NKT_MSG ) ,
time_us : time_us ,
2020-11-24 01:44:09 -04:00
core : core_index ,
2020-11-05 19:30:16 -04:00
timing_count : timing . count ,
dtIMUavg_min : timing . dtIMUavg_min ,
dtIMUavg_max : timing . dtIMUavg_max ,
dtEKFavg_min : timing . dtEKFavg_min ,
dtEKFavg_max : timing . dtEKFavg_max ,
delAngDT_min : timing . delAngDT_min ,
delAngDT_max : timing . delAngDT_max ,
delVelDT_min : timing . delVelDT_min ,
delVelDT_max : timing . delVelDT_max ,
} ;
2020-11-24 01:44:09 -04:00
memset ( & timing , 0 , sizeof ( timing ) ) ;
2020-11-05 19:30:16 -04:00
AP : : logger ( ) . WriteBlock ( & nkt , sizeof ( nkt ) ) ;
}
2019-07-02 21:31:19 -03:00
void NavEKF2 : : Log_Write ( )
{
// only log if enabled
if ( activeCores ( ) < = 0 ) {
return ;
}
2020-11-05 20:02:55 -04:00
if ( lastLogWrite_us = = imuSampleTime_us ) {
// vehicle is doubling up on logging
return ;
}
lastLogWrite_us = imuSampleTime_us ;
2020-11-05 19:30:16 -04:00
const uint64_t time_us = AP : : dal ( ) . micros64 ( ) ;
2019-07-02 21:31:19 -03:00
2020-11-05 19:30:16 -04:00
// note that several of these functions exit-early if they're not
// attempting to log the primary core.
2019-12-06 03:14:10 -04:00
for ( uint8_t i = 0 ; i < activeCores ( ) ; i + + ) {
2020-11-24 01:44:09 -04:00
core [ i ] . Log_Write ( time_us ) ;
2019-07-03 00:58:36 -03:00
}
2020-11-05 19:30:16 -04:00
AP : : dal ( ) . start_frame ( AP_DAL : : FrameType : : LogWriteEKF2 ) ;
2019-07-03 00:58:36 -03:00
}
2020-03-25 00:53:13 -03:00
2020-11-24 01:44:09 -04:00
void NavEKF2_core : : Log_Write ( uint64_t time_us )
2020-03-25 00:53:13 -03:00
{
2020-11-24 01:44:09 -04:00
// note that several of these functions exit-early if they're not
// attempting to log the primary core.
Log_Write_NKF1 ( time_us ) ;
Log_Write_NKF2 ( time_us ) ;
Log_Write_NKF3 ( time_us ) ;
Log_Write_NKF4 ( time_us ) ;
Log_Write_NKF5 ( time_us ) ;
Log_Write_Quaternion ( time_us ) ;
Log_Write_GSF ( time_us ) ;
// write range beacon fusion debug packet if the range value is non-zero
Log_Write_Beacon ( time_us ) ;
Log_Write_Timing ( time_us ) ;
}
void NavEKF2_core : : Log_Write_GSF ( uint64_t time_us ) const
{
if ( yawEstimator = = nullptr ) {
return ;
}
2021-02-17 18:34:13 -04:00
yawEstimator - > Log_Write ( time_us , LOG_NKY0_MSG , LOG_NKY1_MSG , DAL_CORE ( core_index ) ) ;
2020-04-23 19:32:21 -03:00
}