mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: use update_dynamic_notch() directly in rate loop
This commit is contained in:
parent
31dc7a85bf
commit
6ac35ce9af
|
@ -3,6 +3,7 @@
|
|||
#if AP_VEHICLE_ENABLED
|
||||
|
||||
#include "AP_Vehicle.h"
|
||||
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
|
||||
|
||||
#include <AP_BLHeli/AP_BLHeli.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
@ -621,7 +622,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update, 400, 50, 205),
|
||||
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update_parameters, 1, 50, 210),
|
||||
#endif
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED && !AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
|
||||
SCHED_TASK(update_dynamic_notch_at_specified_rate, LOOP_RATE, 200, 215),
|
||||
#endif
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
|
|
|
@ -522,6 +522,13 @@ protected:
|
|||
// Check if this mode can be entered from the GCS
|
||||
bool block_GCS_mode_change(uint8_t mode_num, const uint8_t *mode_list, uint8_t mode_list_length) const;
|
||||
|
||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
// update the harmonic notch
|
||||
void update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch);
|
||||
// run notch update at either loop rate or 200Hz
|
||||
void update_dynamic_notch_at_specified_rate();
|
||||
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
|
||||
private:
|
||||
|
||||
#if AP_SCHEDULER_ENABLED
|
||||
|
@ -536,13 +543,7 @@ private:
|
|||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
// update the harmonic notch for throttle based notch
|
||||
void update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch);
|
||||
|
||||
// update the harmonic notch
|
||||
void update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch);
|
||||
|
||||
// run notch update at either loop rate or 200Hz
|
||||
void update_dynamic_notch_at_specified_rate();
|
||||
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||
|
||||
// decimation for 1Hz update
|
||||
uint8_t one_Hz_counter;
|
||||
|
|
Loading…
Reference in New Issue