mirror of https://github.com/ArduPilot/ardupilot
Plane: allow notch frequencies to be logged at full rate
This commit is contained in:
parent
6e0639ea91
commit
49096422e7
|
@ -262,7 +262,9 @@ void Plane::update_logging25(void)
|
|||
|
||||
if (should_log(MASK_LOG_CTUN)) {
|
||||
Log_Write_Control_Tuning();
|
||||
AP::ins().write_notch_log_messages();
|
||||
if (!should_log(MASK_LOG_NOTCH_FULLRATE)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
#if HAL_GYROFFT_ENABLED
|
||||
gyro_fft.write_log_messages();
|
||||
#endif
|
||||
|
|
|
@ -62,6 +62,9 @@ void Plane::Log_Write_FullRate(void)
|
|||
if (should_log(MASK_LOG_ATTITUDE_FULLRATE)) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
if (should_log(MASK_LOG_NOTCH_FULLRATE)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -608,7 +608,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basic log types by setting this to 65535.
|
||||
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:Performance,4:Control Tuning,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Compass,11:TECS,12:Camera,13:RC Input-Output,14:Rangefinder,19:Raw IMU,20:Fullrate Attitude,21:Video Stabilization
|
||||
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:Performance,4:Control Tuning,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Compass,11:TECS,12:Camera,13:RC Input-Output,14:Rangefinder,19:Raw IMU,20:Fullrate Attitude,21:Video Stabilization,22:Fullrate Notch
|
||||
// @User: Advanced
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
|
|
|
@ -123,6 +123,7 @@ enum log_messages {
|
|||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
#define MASK_LOG_ATTITUDE_FULLRATE (1U<<20)
|
||||
#define MASK_LOG_VIDEO_STABILISATION (1UL<<21)
|
||||
#define MASK_LOG_NOTCH_FULLRATE (1UL<<22)
|
||||
|
||||
enum {
|
||||
CRASH_DETECT_ACTION_BITMASK_DISABLED = 0,
|
||||
|
|
Loading…
Reference in New Issue