mirror of https://github.com/ArduPilot/ardupilot
AP_GyroFFT: make sure the parameters are updated at least once on startup
This commit is contained in:
parent
a2318eea99
commit
6f1d0a4e72
|
@ -327,7 +327,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
|
|||
|
||||
// finally we are done
|
||||
_initialized = true;
|
||||
update_parameters();
|
||||
update_parameters(true);
|
||||
// start running FFTs
|
||||
if (start_update_thread()) {
|
||||
set_analysis_enabled(true);
|
||||
|
@ -477,10 +477,10 @@ bool AP_GyroFFT::start_analysis() {
|
|||
}
|
||||
|
||||
// update calculated values of dynamic parameters - runs at 1Hz
|
||||
void AP_GyroFFT::update_parameters()
|
||||
void AP_GyroFFT::update_parameters(bool force)
|
||||
{
|
||||
// lock contention is very costly, so don't allow configuration updates while flying
|
||||
if (!_initialized || AP::arming().is_armed()) {
|
||||
if ((!_initialized || AP::arming().is_armed()) && !force) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -56,7 +56,7 @@ public:
|
|||
// update the engine state - runs at 400Hz
|
||||
void update();
|
||||
// update calculated values of dynamic parameters - runs at 1Hz
|
||||
void update_parameters();
|
||||
void update_parameters() { update_parameters(false); }
|
||||
// thread for processing gyro data via FFT
|
||||
void update_thread();
|
||||
// start the update thread
|
||||
|
@ -206,6 +206,7 @@ private:
|
|||
uint16_t get_available_samples(uint8_t axis) {
|
||||
return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available();
|
||||
}
|
||||
void update_parameters(bool force);
|
||||
// semaphore for access to shared FFT data
|
||||
HAL_Semaphore _sem;
|
||||
|
||||
|
|
Loading…
Reference in New Issue