mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_NavEKF2: allow logging of IMT data from inside EKF2
This commit is contained in:
parent
2965e67d5d
commit
f92279f436
@ -427,6 +427,13 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
|
||||
// @Units: m/s
|
||||
AP_GROUPINFO("NOAID_NOISE", 35, NavEKF2, _noaidHorizNoise, 10.0f),
|
||||
|
||||
// @Param: LOGGING
|
||||
// @DisplayName: Enable EKF sensor logging
|
||||
// @Description: This enables EKF sensor logging for use by Replay
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LOGGING", 36, NavEKF2, _enable_logging, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -310,6 +310,7 @@ private:
|
||||
AP_Int8 _imuMask; // Bitmask of IMUs to instantiate EKF2 for
|
||||
AP_Int16 _gpsCheckScaler; // Percentage increase to be applied to GPS pre-flight accuracy and drift thresholds
|
||||
AP_Float _noaidHorizNoise; // horizontal position measurement noise assumed when synthesised zero position measurements are used to constrain attitude drift : m
|
||||
AP_Int8 _enable_logging; // Enable logging for Replay
|
||||
|
||||
// Tuning parameters
|
||||
const float gpsNEVelVarAccScale; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration
|
||||
|
@ -9,6 +9,7 @@
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -492,6 +493,9 @@ bool NavEKF2_core::readDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
|
||||
|
||||
if (ins_index < ins.get_gyro_count()) {
|
||||
ins.get_delta_angle(ins_index,dAng);
|
||||
if (frontend->_enable_logging && ins_index == 0) {
|
||||
DataFlash_Class::instance()->Log_Write_IMUDT(ins);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user