AP_GyroFFT: Fix some typos

Fixed some typos found in the code.
This commit is contained in:
Mykhailo Kuznietsov 2023-10-11 18:41:53 +11:00 committed by Peter Barker
parent d86e67b498
commit 83b7bb387d
2 changed files with 3 additions and 3 deletions

View File

@ -362,8 +362,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
}
}
// sample the gyros either by using a gyro window sampled at the gyro rate or making invdividual samples
// called from fast_loop thread - this function does not take out a sempahore to avoid waiting on the FFT thread
// sample the gyros either by using a gyro window sampled at the gyro rate or making individual samples
// called from fast_loop thread - this function does not take out a semaphore to avoid waiting on the FFT thread
void AP_GyroFFT::sample_gyros()
{
if (!analysis_enabled()) {

View File

@ -190,7 +190,7 @@ private:
float update_tl_noise_center_bandwidth_hz(FrequencyPeak peak, uint8_t axis, float value) {
return (_thread_state._center_bandwidth_hz_filtered[peak][axis] = _center_bandwidth_filter[peak].apply(axis, value));
}
// write single log mesages
// write single log messages
void log_noise_peak(uint8_t id, FrequencyPeak peak) const;
// calculate the peak noise frequency
void calculate_noise(bool calibrating, const EngineConfig& config);