mirror of https://github.com/ArduPilot/ardupilot
Copter: add fast harmonic notch logging
This commit is contained in:
parent
1c8d206dfb
commit
9a450a05bb
|
@ -491,6 +491,9 @@ void Copter::loop_rate_logging()
|
|||
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
if (should_log(MASK_LOG_FTN_FAST)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
}
|
||||
|
||||
// ten_hz_logging_loop
|
||||
|
@ -703,7 +706,9 @@ void Copter::update_altitude()
|
|||
|
||||
if (should_log(MASK_LOG_CTUN)) {
|
||||
Log_Write_Control_Tuning();
|
||||
if (!should_log(MASK_LOG_FTN_FAST)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
#if HAL_GYROFFT_ENABLED
|
||||
gyro_fft.write_log_messages();
|
||||
#endif
|
||||
|
|
|
@ -322,7 +322,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: 4 byte bitmap of log types to enable
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW,20:VideoStabilization
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW,20:VideoStabilization,21:Fast harmonic notch updates
|
||||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
|
|
|
@ -144,6 +144,7 @@ enum LoggingParameters {
|
|||
#define MASK_LOG_IMU_FAST (1UL<<18)
|
||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
#define MASK_LOG_VIDEO_STABILISATION (1UL<<20)
|
||||
#define MASK_LOG_FTN_FAST (1UL<<21)
|
||||
#define MASK_LOG_ANY 0xFFFF
|
||||
|
||||
// Radio failsafe definitions (FS_THR parameter)
|
||||
|
|
Loading…
Reference in New Issue