mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: allow HarmonicNotches to be compiled out of the code
This commit is contained in:
parent
4569b1ba14
commit
626d64f503
|
@ -273,9 +273,11 @@ void Plane::update_logging25(void)
|
|||
|
||||
if (should_log(MASK_LOG_CTUN)) {
|
||||
Log_Write_Control_Tuning();
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
if (!should_log(MASK_LOG_NOTCH_FULLRATE)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
#endif
|
||||
#if HAL_GYROFFT_ENABLED
|
||||
gyro_fft.write_log_messages();
|
||||
#endif
|
||||
|
|
|
@ -65,9 +65,11 @@ void Plane::Log_Write_FullRate(void)
|
|||
if (should_log(MASK_LOG_ATTITUDE_FULLRATE)) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
if (should_log(MASK_LOG_NOTCH_FULLRATE)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -1481,6 +1481,7 @@ void Plane::load_parameters(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
|
||||
if (!ins.harmonic_notches[1].params.enabled()) {
|
||||
// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch
|
||||
|
@ -1495,7 +1496,8 @@ void Plane::load_parameters(void)
|
|||
AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);
|
||||
}
|
||||
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
|
||||
|
||||
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Mar-2022
|
||||
#if AP_FENCE_ENABLED
|
||||
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, true);
|
||||
|
|
Loading…
Reference in New Issue