mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
AP_InertialSensor: move INS_HNTC2 to a new parameter table ID
This commit is contained in:
parent
4289b6bc1b
commit
5db3a06751
@ -533,9 +533,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
|
||||
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
|
||||
AP_GROUPINFO("FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, HAL_DEFAULT_INS_FAST_SAMPLE),
|
||||
|
||||
// @Group: NOTCH_
|
||||
// @Path: ../Filter/HarmonicNotchFilter.cpp
|
||||
AP_SUBGROUPINFO(_notch_filter, "NOTCH_", 37, AP_InertialSensor, HarmonicNotchFilterParams),
|
||||
// index 37 was NOTCH_
|
||||
|
||||
// @Group: LOG_
|
||||
// @Path: ../AP_InertialSensor/BatchSampler.cpp
|
||||
@ -552,6 +550,10 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
|
||||
// @Path: ../Filter/HarmonicNotchFilter.cpp
|
||||
AP_SUBGROUPINFO(_harmonic_notch_filter, "HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams),
|
||||
|
||||
// @Group: HNTC2_
|
||||
// @Path: ../Filter/HarmonicNotchFilter.cpp
|
||||
AP_SUBGROUPINFO(_notch_filter, "HNTC2_", 53, AP_InertialSensor, HarmonicNotchFilterParams),
|
||||
|
||||
// @Param: GYRO_RATE
|
||||
// @DisplayName: Gyro rate for IMUs with Fast Sampling enabled
|
||||
// @Description: Gyro rate for IMUs with fast sampling enabled. The gyro rate is the sample rate at which the IMU filters operate and needs to be at least double the maximum filter frequency. If the sensor does not support the selected rate the next highest supported rate will be used. For IMUs which do not support fast sampling this setting is ignored and the default gyro rate of 1Khz is used.
|
||||
|
@ -303,6 +303,9 @@ public:
|
||||
// check for vibration movement. True when all axis show nearly zero movement
|
||||
bool is_still();
|
||||
|
||||
// return true if notch enabled
|
||||
bool gyro_notch_enabled(void) const { return _notch_filter.enabled(); }
|
||||
|
||||
// return true if harmonic notch enabled
|
||||
bool gyro_harmonic_notch_enabled(void) const { return _harmonic_notch_filter.enabled(); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user