2023-07-13 21:58:07 -03:00
# include <AP_Logger/AP_Logger_config.h>
# if HAL_LOGGING_ENABLED
2019-07-02 20:52:45 -03:00
# include "AP_NavEKF3.h"
2020-11-10 07:51:23 -04:00
# include "AP_NavEKF3_core.h"
2019-07-02 20:52:45 -03:00
# include <AP_HAL/HAL.h>
# include <AP_Logger/AP_Logger.h>
2020-11-05 19:30:16 -04:00
# include <AP_DAL/AP_DAL.h>
2021-05-04 08:12:23 -03:00
# pragma GCC diagnostic ignored "-Wnarrowing"
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKF1 ( uint64_t time_us ) const
2019-07-02 20:52:45 -03:00
{
2020-11-05 19:30:16 -04:00
// Write first EKF packet
2019-07-02 20:52:45 -03:00
Vector3f euler ;
Vector2f posNE ;
float posD ;
Vector3f velNED ;
Vector3f gyroBias ;
float posDownDeriv ;
Location originLLH ;
2020-11-10 07:51:23 -04:00
getEulerAngles ( euler ) ;
getVelNED ( velNED ) ;
getPosNE ( posNE ) ;
getPosD ( posD ) ;
getGyroBias ( gyroBias ) ;
posDownDeriv = getPosDownDerivative ( ) ;
if ( ! getOriginLLH ( originLLH ) ) {
2019-07-02 20:52:45 -03:00
originLLH . alt = 0 ;
}
2020-12-03 06:13:12 -04:00
const struct log_XKF1 pkt {
2019-12-06 03:16:12 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKF1_MSG ) ,
2019-07-02 20:52:45 -03:00
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-02 20:52:45 -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 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt , sizeof ( pkt ) ) ;
}
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKF2 ( uint64_t time_us ) const
2019-07-02 22:48:50 -03:00
{
2019-07-02 20:52:45 -03:00
// Write second EKF packet
Vector3f accelBias ;
Vector3f wind ;
Vector3f magNED ;
Vector3f magXYZ ;
2020-11-10 07:51:23 -04:00
getAccelBias ( accelBias ) ;
getWind ( wind ) ;
getMagNED ( magNED ) ;
getMagXYZ ( magXYZ ) ;
2020-11-20 17:39:04 -04:00
Vector2f dragInnov ;
float betaInnov = 0 ;
getSynthAirDataInnovations ( dragInnov , betaInnov ) ;
2020-03-29 19:52:10 -03:00
const struct log_XKF2 pkt2 {
2019-12-06 03:16:12 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKF2_MSG ) ,
2019-07-02 20:52:45 -03:00
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-02 20:52:45 -03:00
accBiasX : ( int16_t ) ( 100 * accelBias . x ) ,
accBiasY : ( int16_t ) ( 100 * accelBias . y ) ,
accBiasZ : ( int16_t ) ( 100 * accelBias . 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 ) ,
2020-11-20 17:39:04 -04:00
magZ : ( int16_t ) ( magXYZ . z ) ,
innovDragX : dragInnov . x ,
innovDragY : dragInnov . y ,
innovSideslip : betaInnov
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt2 , sizeof ( pkt2 ) ) ;
}
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKFS ( uint64_t time_us ) const
2020-06-23 13:35:34 -03:00
{
// Write sensor selection EKF packet
2020-12-01 20:49:19 -04:00
const struct log_XKFS pkt {
2020-06-23 13:35:34 -03:00
LOG_PACKET_HEADER_INIT ( LOG_XKFS_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
mag_index : magSelectIndex ,
baro_index : selected_baro ,
gps_index : selected_gps ,
2021-07-16 01:26:35 -03:00
airspeed_index : getActiveAirspeed ( ) ,
2023-09-27 00:26:59 -03:00
source_set : frontend - > sources . getPosVelYawSourceSet ( ) ,
2023-09-27 02:35:31 -03:00
gps_good_to_align : gpsGoodToAlign ,
2024-03-21 14:56:00 -03:00
wait_for_gps_checks : waitingForGpsChecks ,
mag_fusion : ( uint8_t ) magFusionSel
2020-06-23 13:35:34 -03:00
} ;
AP : : logger ( ) . WriteBlock ( & pkt , sizeof ( pkt ) ) ;
}
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKF3 ( uint64_t time_us ) const
2019-07-02 22:48:50 -03:00
{
2019-07-02 20:52:45 -03:00
// Write third EKF packet
Vector3f velInnov ;
Vector3f posInnov ;
Vector3f magInnov ;
float tasInnov = 0 ;
float yawInnov = 0 ;
2020-11-10 07:51:23 -04:00
getInnovations ( velInnov , posInnov , magInnov , tasInnov , yawInnov ) ;
2020-12-01 20:49:19 -04:00
const struct log_XKF3 pkt3 {
2019-12-06 03:16:12 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKF3_MSG ) ,
2019-07-02 20:52:45 -03:00
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-02 20:52:45 -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 03:21:46 -03:00
innovVT : ( int16_t ) ( 100 * tasInnov ) ,
2020-11-10 07:51:23 -04:00
rerr : frontend - > coreRelativeErrors [ core_index ] ,
errorScore : frontend - > coreErrorScores [ core_index ]
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt3 , sizeof ( pkt3 ) ) ;
}
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKF4 ( uint64_t time_us ) const
2019-07-02 22:48:50 -03:00
{
2019-07-02 20:52:45 -03:00
// Write fourth EKF packet
float velVar = 0 ;
float posVar = 0 ;
float hgtVar = 0 ;
Vector3f magVar ;
float tasVar = 0 ;
2020-11-10 07:51:23 -04:00
uint16_t _faultStatus = 0 ;
2019-07-02 20:52:45 -03:00
Vector2f offset ;
2021-01-21 06:20:43 -04:00
const uint8_t timeoutStatus =
posTimeout < < 0 |
velTimeout < < 1 |
hgtTimeout < < 2 |
magTimeout < < 3 |
2022-05-09 23:59:57 -03:00
tasTimeout < < 4 |
dragTimeout < < 5 ;
2021-01-21 06:20:43 -04:00
2019-07-02 20:52:45 -03:00
nav_filter_status solutionStatus { } ;
2020-11-10 07:51:23 -04:00
getVariances ( velVar , posVar , hgtVar , magVar , tasVar , offset ) ;
2021-05-04 08:12:23 -03:00
float tempVar = fmaxF ( fmaxF ( magVar . x , magVar . y ) , magVar . z ) ;
2020-11-10 07:51:23 -04:00
getFilterFaults ( _faultStatus ) ;
getFilterStatus ( solutionStatus ) ;
2021-12-02 19:55:33 -04:00
const struct log_XKF4 pkt4 {
2019-12-06 03:16:12 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKF4_MSG ) ,
2019-07-02 20:52:45 -03:00
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-02 20:52:45 -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 : sqrtF ( MAX ( tiltErrorVariance , 0.0f ) ) , // estimated 1-sigma tilt error in radians
2021-02-27 08:40:42 -04:00
offsetNorth : offset . x ,
offsetEast : offset . y ,
2020-11-10 07:51:23 -04:00
faults : _faultStatus ,
timeouts : timeoutStatus ,
solution : solutionStatus . value ,
2021-05-29 23:24:16 -03:00
gps : gpsCheckStatus . value ,
2020-11-10 07:51:23 -04:00
primary : frontend - > getPrimaryCoreIndex ( )
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt4 , sizeof ( pkt4 ) ) ;
}
2019-07-02 20:52:45 -03:00
2019-07-02 22:48:50 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_XKF5 ( uint64_t time_us ) const
2019-07-02 22:48:50 -03:00
{
2020-11-10 07:51:23 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
2021-12-02 19:55:33 -04:00
const struct log_XKF5 pkt5 {
2019-07-02 20:52:45 -03:00
LOG_PACKET_HEADER_INIT ( LOG_XKF5_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -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
2021-08-16 10:00:52 -03:00
FIX : ( int16_t ) ( 1000 * flowInnov [ 0 ] ) , // optical flow LOS rate vector innovations from the main nav filter
FIY : ( int16_t ) ( 1000 * flowInnov [ 1 ] ) , // optical flow LOS rate vector innovations from the main nav filter
2021-09-11 07:34:45 -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-10 07:51:23 -04:00
offset : ( int16_t ) ( 100 * terrainState ) , // filter ground offset state error
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 ) ) , // note Popt is constrained to be non-negative in EstimateTerrainOffset()
2020-11-10 07:51:23 -04:00
angErr : ( float ) outputTrackError . x , // output predictor angle error
velErr : ( float ) outputTrackError . y , // output predictor velocity error
posErr : ( float ) outputTrackError . z // output predictor position tracking error
2020-06-19 03:21:46 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt5 , sizeof ( pkt5 ) ) ;
}
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_Quaternion ( uint64_t time_us ) const
2019-07-02 22:48:50 -03:00
{
2019-07-02 20:52:45 -03:00
// log quaternion
Quaternion quat ;
2020-11-10 07:51:23 -04:00
getQuaternion ( quat ) ;
2020-12-01 20:49:19 -04:00
const struct log_XKQ pktq1 {
2019-12-06 03:16:12 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKQ_MSG ) ,
2019-07-02 20:52:45 -03:00
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2019-07-02 20:52:45 -03:00
q1 : quat . q1 ,
q2 : quat . q2 ,
q3 : quat . q3 ,
q4 : quat . q4
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pktq1 , sizeof ( pktq1 ) ) ;
}
2019-07-02 20:52:45 -03:00
2022-01-27 20:09:44 -04:00
# if EK3_FEATURE_BEACON_FUSION
2020-11-10 07:51:23 -04:00
// logs beacon information, one beacon per call
void NavEKF3_core : : Log_Write_Beacon ( uint64_t time_us )
2019-07-02 22:48:50 -03:00
{
2020-11-10 07:51:23 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
2022-04-15 05:38:34 -03:00
if ( ! statesInitialised | | rngBcn . N = = 0 | | rngBcn . fusionReport = = nullptr ) {
2020-11-10 07:51:23 -04:00
return ;
}
// Ensure that beacons are not skipped due to calling this function at a rate lower than the updates
2024-02-26 00:09:46 -04:00
if ( rngBcn . fuseDataReportIndex > = rngBcn . N | |
rngBcn . fuseDataReportIndex > rngBcn . numFusionReports ) {
2022-04-15 05:38:34 -03:00
rngBcn . fuseDataReportIndex = 0 ;
2020-11-10 07:51:23 -04:00
}
2022-04-15 05:38:34 -03:00
const auto & report = rngBcn . fusionReport [ rngBcn . fuseDataReportIndex ] ;
2020-11-10 07:51:23 -04:00
2019-07-02 20:52:45 -03:00
// write range beacon fusion debug packet if the range value is non-zero
2020-11-10 07:51:23 -04:00
if ( report . rng < = 0.0f ) {
2022-04-15 05:38:34 -03:00
rngBcn . fuseDataReportIndex + + ;
2020-11-10 07:51:23 -04:00
return ;
2019-07-02 20:52:45 -03:00
}
2020-11-10 07:51:23 -04:00
2020-12-01 20:49:19 -04:00
const struct log_XKF0 pkt10 {
2020-12-02 19:43:39 -04:00
LOG_PACKET_HEADER_INIT ( LOG_XKF0_MSG ) ,
2020-11-10 07:51:23 -04:00
time_us : time_us ,
core : DAL_CORE ( core_index ) ,
2022-04-15 05:38:34 -03:00
ID : rngBcn . fuseDataReportIndex ,
2020-11-10 07:51:23 -04:00
rng : ( int16_t ) ( 100 * report . rng ) ,
innov : ( int16_t ) ( 100 * report . innov ) ,
2021-05-04 08:12:23 -03:00
sqrtInnovVar : ( uint16_t ) ( 100 * sqrtF ( report . innovVar ) ) ,
testRatio : ( uint16_t ) ( 100 * constrain_ftype ( report . testRatio , 0.0f , 650.0f ) ) ,
2020-11-10 07:51:23 -04:00
beaconPosN : ( int16_t ) ( 100 * report . beaconPosNED . x ) ,
beaconPosE : ( int16_t ) ( 100 * report . beaconPosNED . y ) ,
beaconPosD : ( int16_t ) ( 100 * report . beaconPosNED . z ) ,
2022-04-15 05:38:34 -03:00
offsetHigh : ( int16_t ) ( 100 * rngBcn . posDownOffsetMax ) ,
offsetLow : ( int16_t ) ( 100 * rngBcn . posDownOffsetMin ) ,
posN : ( int16_t ) ( 100 * rngBcn . receiverPos . x ) ,
posE : ( int16_t ) ( 100 * rngBcn . receiverPos . y ) ,
posD : ( int16_t ) ( 100 * rngBcn . receiverPos . z )
2020-11-10 07:51:23 -04:00
} ;
AP : : logger ( ) . WriteBlock ( & pkt10 , sizeof ( pkt10 ) ) ;
2022-04-15 05:38:34 -03:00
rngBcn . fuseDataReportIndex + + ;
2019-07-02 22:48:50 -03:00
}
2022-01-27 20:09:44 -04:00
# endif // EK3_FEATURE_BEACON_FUSION
2019-07-02 22:48:50 -03:00
2021-05-29 23:07:39 -03:00
# if EK3_FEATURE_BODY_ODOM
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_BodyOdom ( uint64_t time_us )
2019-07-02 22:48:50 -03:00
{
2020-11-10 07:51:23 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
2021-05-29 23:07:39 -03:00
const uint32_t updateTime_ms = MAX ( bodyOdmDataDelayed . time_ms , wheelOdmDataDelayed . time_ms ) ;
2019-07-02 20:52:45 -03:00
if ( updateTime_ms > lastUpdateTime_ms ) {
2020-12-01 20:49:19 -04:00
const struct log_XKFD pkt11 {
2019-07-02 20:52:45 -03:00
LOG_PACKET_HEADER_INIT ( LOG_XKFD_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
2021-05-29 23:07:39 -03:00
velInnovX : innovBodyVel [ 0 ] ,
velInnovY : innovBodyVel [ 1 ] ,
velInnovZ : innovBodyVel [ 2 ] ,
velInnovVarX : varInnovBodyVel [ 0 ] ,
velInnovVarY : varInnovBodyVel [ 1 ] ,
velInnovVarZ : varInnovBodyVel [ 2 ]
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pkt11 , sizeof ( pkt11 ) ) ;
2019-07-02 20:52:45 -03:00
lastUpdateTime_ms = updateTime_ms ;
}
2019-07-02 22:48:50 -03:00
}
2021-05-29 23:07:39 -03:00
# endif
2019-07-02 20:52:45 -03:00
2021-12-26 18:07:02 -04:00
void NavEKF3_core : : Log_Write_State_Variances ( uint64_t time_us )
2019-07-02 22:48:50 -03:00
{
2020-11-10 07:51:23 -04:00
if ( core_index ! = frontend - > primary ) {
2020-11-05 19:30:16 -04:00
// log only primary instance for now
return ;
}
if ( AP : : dal ( ) . millis ( ) - lastEkfStateVarLogTime_ms > 490 ) {
lastEkfStateVarLogTime_ms = AP : : dal ( ) . millis ( ) ;
2020-12-01 20:49:19 -04:00
const struct log_XKV pktv1 {
2019-07-02 20:52:45 -03:00
LOG_PACKET_HEADER_INIT ( LOG_XKV1_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
v00 : P [ 0 ] [ 0 ] ,
v01 : P [ 1 ] [ 1 ] ,
v02 : P [ 2 ] [ 2 ] ,
v03 : P [ 3 ] [ 3 ] ,
v04 : P [ 4 ] [ 4 ] ,
v05 : P [ 5 ] [ 5 ] ,
v06 : P [ 6 ] [ 6 ] ,
v07 : P [ 7 ] [ 7 ] ,
v08 : P [ 8 ] [ 8 ] ,
v09 : P [ 9 ] [ 9 ] ,
v10 : P [ 10 ] [ 10 ] ,
v11 : P [ 11 ] [ 11 ]
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pktv1 , sizeof ( pktv1 ) ) ;
2020-12-01 20:49:19 -04:00
const struct log_XKV pktv2 {
2019-07-02 20:52:45 -03:00
LOG_PACKET_HEADER_INIT ( LOG_XKV2_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -04:00
core : DAL_CORE ( core_index ) ,
v00 : P [ 12 ] [ 12 ] ,
v01 : P [ 13 ] [ 13 ] ,
v02 : P [ 14 ] [ 14 ] ,
v03 : P [ 15 ] [ 15 ] ,
v04 : P [ 16 ] [ 16 ] ,
v05 : P [ 17 ] [ 17 ] ,
v06 : P [ 18 ] [ 18 ] ,
v07 : P [ 19 ] [ 19 ] ,
v08 : P [ 20 ] [ 20 ] ,
v09 : P [ 21 ] [ 21 ] ,
v10 : P [ 22 ] [ 22 ] ,
v11 : P [ 23 ] [ 23 ]
2019-07-02 20:52:45 -03:00
} ;
2019-07-02 22:48:50 -03:00
AP : : logger ( ) . WriteBlock ( & pktv2 , sizeof ( pktv2 ) ) ;
}
}
void NavEKF3 : : 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 ;
2019-07-02 22:48:50 -03:00
2020-11-05 19:30:16 -04:00
uint64_t time_us = AP : : dal ( ) . micros64 ( ) ;
2019-07-02 22:48:50 -03:00
2019-12-06 03:16:12 -04:00
for ( uint8_t i = 0 ; i < activeCores ( ) ; i + + ) {
2020-11-10 07:51:23 -04:00
core [ i ] . Log_Write ( time_us ) ;
}
AP : : dal ( ) . start_frame ( AP_DAL : : FrameType : : LogWriteEKF3 ) ;
}
2020-11-05 19:30:16 -04:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write ( uint64_t time_us )
{
2022-07-27 21:56:33 -03:00
const auto level = frontend - > _log_level ;
if ( level = = NavEKF3 : : LogLevel : : NONE ) { // no logging from EK3_LOG_LEVEL param
return ;
}
Log_Write_XKF4 ( time_us ) ;
if ( level = = NavEKF3 : : LogLevel : : XKF4 ) { // only log XKF4 scaled innovations
return ;
}
Log_Write_GSF ( time_us ) ;
if ( level = = NavEKF3 : : LogLevel : : XKF4_GSF ) { // only log XKF4 scaled innovations and GSF, otherwise log everything
return ;
}
2020-11-10 07:51:23 -04:00
// note that several of these functions exit-early if they're not
// attempting to log the primary core.
Log_Write_XKF1 ( time_us ) ;
Log_Write_XKF2 ( time_us ) ;
Log_Write_XKF3 ( time_us ) ;
Log_Write_XKF5 ( time_us ) ;
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
Log_Write_XKFS ( time_us ) ;
Log_Write_Quaternion ( time_us ) ;
2022-07-27 21:56:33 -03:00
2020-11-05 19:30:16 -04:00
2022-01-27 20:09:44 -04:00
# if EK3_FEATURE_BEACON_FUSION
2020-11-10 07:51:23 -04:00
// write range beacon fusion debug packet if the range value is non-zero
Log_Write_Beacon ( time_us ) ;
2022-01-27 20:09:44 -04:00
# endif
2019-07-02 22:48:50 -03:00
2021-01-18 21:53:20 -04:00
# if EK3_FEATURE_BODY_ODOM
2020-11-10 07:51:23 -04:00
// write debug data for body frame odometry fusion
Log_Write_BodyOdom ( time_us ) ;
2021-01-18 21:53:20 -04:00
# endif
2019-07-02 22:48:50 -03:00
2020-11-10 07:51:23 -04:00
// log state variances every 0.49s
Log_Write_State_Variances ( time_us ) ;
2020-11-05 19:30:16 -04:00
2020-11-10 07:51:23 -04:00
Log_Write_Timing ( time_us ) ;
2020-11-05 19:30:16 -04:00
}
2019-07-02 20:52:45 -03:00
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_Timing ( uint64_t time_us )
2020-11-05 19:30:16 -04:00
{
2019-07-02 20:52:45 -03:00
// log EKF timing statistics every 5s
2020-11-05 19:30:16 -04:00
if ( AP : : dal ( ) . millis ( ) - lastTimingLogTime_ms < = 5000 ) {
return ;
2019-07-02 20:52:45 -03:00
}
2020-11-05 19:30:16 -04:00
lastTimingLogTime_ms = AP : : dal ( ) . millis ( ) ;
const struct log_XKT xkt {
LOG_PACKET_HEADER_INIT ( LOG_XKT_MSG ) ,
time_us : time_us ,
2020-11-10 07:51:23 -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-10 07:51:23 -04:00
memset ( & timing , 0 , sizeof ( timing ) ) ;
2020-11-05 19:30:16 -04:00
AP : : logger ( ) . WriteBlock ( & xkt , sizeof ( xkt ) ) ;
2019-07-02 20:52:45 -03:00
}
2020-11-10 07:51:23 -04:00
void NavEKF3_core : : Log_Write_GSF ( uint64_t time_us )
2020-03-10 03:48:08 -03:00
{
2020-11-10 07:51:23 -04:00
if ( yawEstimator = = nullptr ) {
return ;
}
2021-02-17 18:34:14 -04:00
yawEstimator - > Log_Write ( time_us , LOG_XKY0_MSG , LOG_XKY1_MSG , DAL_CORE ( core_index ) ) ;
2020-04-23 19:32:21 -03:00
}
2023-07-13 21:58:07 -03:00
# endif // HAL_LOGGING_ENABLED