AP_GyroFFT: new FFT library for motor peak analysis using HAL DSP abstraction

add dynamic gyro windows
control inclusion based on HAL_WITH_DSP and GYROFFT_ENABLED
target appropriate ARM cpus
constrain window sizes to be achievable
improve FFT signal accuracy through configurable window overlap and quinn's estimator
calculate energy weighted center frequency
add support for learning hover frequency and throttle reference
calculate power spectrum rather than amplitude
record noise as a per-bin power spectrum
calculate true SNR per-bin and use that to determine there is a signal
add user config for SNR signal level
constrain frequency scanning to MAXHZ
calculate and learn the peak bandwidth at the configured attenuation
allow enabling/disabling dynamically through rc function
MAXHZ should be below Nyquist
Incorporate full range of MAXHZ to MINHZ
update FFT analysis in a separate thread
allocate memory in a specific region
constrain window size by CPU class
do not allocate any resources when not enabled
Prevent self-check and analysis interfering with each other
put configuration and initialization to AP_Vehicle
add logging
fix significant issues with threading, locking and sample buffer access
use both calculated noise peaks together with the harmonic notch configuration to detemine which peak represents the fundamental harmonic that should be tracked
record harmonic fit
add CMSIS 5 libraries and headers
allow larger FFT lengths on Linux and SITL
This commit is contained in:
Andy Piper 2019-08-15 22:12:20 +01:00 committed by Andrew Tridgell
parent 7571b4d95c
commit 7d36bc4422
13 changed files with 9153 additions and 0 deletions

View File

@ -0,0 +1,756 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Code by Andy Piper with help from betaflight
*/
#include "AP_GyroFFT.h"
#if HAL_GYROFFT_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <Filter/HarmonicNotchFilter.h>
extern const AP_HAL::HAL& hal;
#define FFT_DEFAULT_WINDOW_SIZE 32
#define FFT_DEFAULT_WINDOW_OVERLAP 0.5f
#define FFT_THR_REF_DEFAULT 0.35f // the estimated throttle reference, 0 ~ 1
#define FFT_SNR_DEFAULT 25.0f // a higher SNR is safer and this works quite well on a Pixracer
#define FFT_STACK_SIZE 1024
#define FFT_REQUIRED_HARMONIC_FIT 10.0f
// table of user settable parameters
const AP_Param::GroupInfo AP_GyroFFT::var_info[] = {
// @Param: ENABLE
// @DisplayName: Enable
// @Description: Enable Gyro FFT analyser
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FLAGS("ENABLE", 1, AP_GyroFFT, _enable, 0, AP_PARAM_FLAG_ENABLE),
// @Param: MINHZ
// @DisplayName: Minimum Frequency
// @Description: Lower bound of FFT frequency detection in Hz.
// @Range: 10 400
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("MINHZ", 2, AP_GyroFFT, _fft_min_hz, 80),
// @Param: MAXHZ
// @DisplayName: Maximum Frequency
// @Description: Upper bound of FFT frequency detection in Hz.
// @Range: 10 400
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("MAXHZ", 3, AP_GyroFFT, _fft_max_hz, 200),
// @Param: SAMPLE_MODE
// @DisplayName: Sample Mode
// @Description: Sampling mode (and therefore rate). 0: Gyro rate sampling, 1: Fast loop rate sampling, 2: Fast loop rate / 2 sampling, 3: Fast loop rate / 3 sampling. Takes effect on reboot.
// @Range: 0 4
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("SAMPLE_MODE", 4, AP_GyroFFT, _sample_mode, 0),
// @Param: WINDOW_SIZE
// @DisplayName: FFT window size
// @Description: Size of window to be used in FFT calculations. Takes effect on reboot. Must be a power of 2 and between 32 and 1024. Larger windows give greater frequency resolution but poorer time resolution, consume more CPU time and may not be appropriate for all vehicles. Time and frequency resolution are given by the sample-rate / window-size. Windows of 256 are only really recommended for F7 class boards, windows of 512 or more H7 class.
// @Range: 32 1024
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("WINDOW_SIZE", 5, AP_GyroFFT, _window_size, FFT_DEFAULT_WINDOW_SIZE),
// @Param: WINDOW_OLAP
// @DisplayName: FFT window overlap
// @Description: Percentage of window to be overlapped before another frame is process. Takes effect on reboot. A good default is 50% overlap. Higher overlap results in more processed frames but not necessarily more temporal resolution. Lower overlap results in lost information at the frame edges.
// @Range: 0 0.9
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("WINDOW_OLAP", 6, AP_GyroFFT, _window_overlap, FFT_DEFAULT_WINDOW_OVERLAP),
// @Param: FREQ_HOVER
// @DisplayName: FFT learned hover frequency
// @Description: The learned hover noise frequency
// @Range: 0 250
// @User: Advanced
AP_GROUPINFO("FREQ_HOVER", 7, AP_GyroFFT, _freq_hover_hz, 80.0f),
// @Param: THR_REF
// @DisplayName: FFT learned thrust reference
// @Description: FFT learned thrust reference for the hover frequency and FFT minimum frequency.
// @Range: 0.01 0.9
// @User: Advanced
AP_GROUPINFO("THR_REF", 8, AP_GyroFFT, _throttle_ref, FFT_THR_REF_DEFAULT),
// @Param: SNR_REF
// @DisplayName: FFT SNR reference threshold
// @Description: FFT SNR reference threshold in dB at which a signal is determined to be present.
// @Range: 0.0 100.0
// @User: Advanced
AP_GROUPINFO("SNR_REF", 9, AP_GyroFFT, _snr_threshold_db, FFT_SNR_DEFAULT),
// @Param: ATT_REF
// @DisplayName: FFT attenuation for bandwidth calculation
// @Description: FFT attenuation level in dB for bandwidth calculation and peak detection. The bandwidth is calculated by comparing peak power output with the attenuated version. The default of 15 has shown to be a good compromise in both simulations and real flight.
// @Range: 0 100
// @User: Advanced
AP_GROUPINFO("ATT_REF", 10, AP_GyroFFT, _attenuation_power_db, 15),
// @Param: BW_HOVER
// @DisplayName: FFT learned bandwidth at hover
// @Description: FFT learned bandwidth at hover for the attenuation frequencies.
// @Range: 0 200
// @User: Advanced
AP_GROUPINFO("BW_HOVER", 11, AP_GyroFFT, _bandwidth_hover_hz, 20),
AP_GROUPEND
};
// The FFT splits the frequency domain into an number of bins
// A sampling frequency of 1000 and max frequency (Nyquist) of 500 at a window size of 32 gives 16 frequency bins each 31.25Hz wide
// The first bin is used to store the DC and Nyquist values combined.
// Eg [DC/Nyquist], [16,47), [47,78), [78,109) etc
// For a loop rate of 800Hz, 16 bins each 25Hz wide
// Eg X[0]=[DC/Nyquist], X[1]=[12,37), X[2]=[37,62), X[3]=[62,87), X[4]=[87,112)
// So middle frequency is X[n] * 25 and the range is X[n] * 25 - 12 < f < X[n] * 25 + 12
// Maximum tolerated number of cycles with missing signal
#define FFT_MAX_MISSED_UPDATES 3
const extern AP_HAL::HAL& hal;
AP_GyroFFT::AP_GyroFFT()
{
_thread_state._noise_needs_calibration = 0x07; // all axes need calibration
AP_Param::setup_object_defaults(this, var_info);
if (_singleton != nullptr) {
AP_HAL::panic("AP_GyroFFT must be singleton");
}
_singleton = this;
}
// initialize the FFT parameters and engine
void AP_GyroFFT::init(uint32_t target_looptime_us)
{
// if FFT analysis is not enabled we don't want to allocate any of the associated resources
if (!_enable) {
return;
}
_ins = &AP::ins();
// sanity check
if (_ins->get_raw_gyro_rate_hz() == 0) {
AP_HAL::panic("AP_GyroFFT must be initialized after AP_InertialSensor");
}
// check that we support the window size requested and it is a power of 2
_window_size = 1 << lrintf(log2f(_window_size.get()));
#if defined(STM32H7) || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
_window_size = constrain_int16(_window_size, 32, 1024);
#else
_window_size = constrain_int16(_window_size, 32, 256);
#endif
// check that we have enough memory for the window size requested
// INS: XYZ_AXIS_COUNT * INS_MAX_INSTANCES * _window_size, DSP: 3 * _window_size, FFT: XYZ_AXIS_COUNT + 3 * _window_size
const uint32_t allocation_count = (XYZ_AXIS_COUNT * INS_MAX_INSTANCES + 3 + XYZ_AXIS_COUNT + 3) * sizeof(float);
if (allocation_count * FFT_DEFAULT_WINDOW_SIZE > hal.util->available_memory() / 2) {
gcs().send_text(MAV_SEVERITY_WARNING, "AP_GyroFFT: disabled, required %u bytes", (unsigned int)allocation_count * FFT_DEFAULT_WINDOW_SIZE);
return;
} else if (allocation_count * _window_size > hal.util->available_memory() / 2) {
gcs().send_text(MAV_SEVERITY_WARNING, "AP_GyroFFT: req alloc %u bytes (free=%u)", (unsigned int)allocation_count * _window_size, (unsigned int)hal.util->available_memory());
_window_size = FFT_DEFAULT_WINDOW_SIZE;
}
// save any changes that were made
_window_size.save();
// determine the FFT sample rate based on the gyro rate, loop rate and configuration
if (_sample_mode == 0) {
_fft_sampling_rate_hz = _ins->get_raw_gyro_rate_hz();
} else {
const uint16_t loop_rate_hz = 1000*1000UL / target_looptime_us;
_fft_sampling_rate_hz = loop_rate_hz / _sample_mode;
for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
_downsampled_gyro_data[axis] = (float*)hal.util->malloc_type(sizeof(float) * _window_size, DSP_MEM_REGION);
if (_downsampled_gyro_data[axis] == nullptr) {
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to allocate window for AP_GyroFFT");
return;
}
}
}
_current_sample_mode = _sample_mode;
_ref_energy = new Vector3f[_window_size];
if (_ref_energy == nullptr) {
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to allocate window for AP_GyroFFT");
return;
}
// make the gyro window match the window size plus the maximum that can be in play from the backend
if (!_ins->set_gyro_window_size(_window_size + INS_MAX_GYRO_WINDOW_SAMPLES)) {
return;
}
// current read marker is the beginning of the window
if (_sample_mode == 0) {
_circular_buffer_idx = _ins->get_raw_gyro_window_index();
} else {
_circular_buffer_idx = 0;
}
// initialise the HAL DSP subsystem
_state = hal.dsp->fft_init(_window_size, _fft_sampling_rate_hz);
if (_state == nullptr) {
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialize DSP engine");
return;
}
// number of samples needed before a new frame can be processed
_window_overlap = constrain_float(_window_overlap, 0.0f, 0.9f);
_window_overlap.save();
_samples_per_frame = (1.0f - _window_overlap) * _window_size;
_samples_per_frame = 1 << lrintf(log2f(_samples_per_frame));
// The update rate for the output
const float output_rate = _fft_sampling_rate_hz / _samples_per_frame;
// establish suitable defaults for the detected values
for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
_thread_state._center_freq_hz[axis] = _fft_min_hz;
_thread_state._center_freq_hz_filtered[axis] = _fft_min_hz;
// calculate low-pass filter characteristics based on overlap size
_center_freq_filter[axis].set_cutoff_frequency(output_rate, output_rate * 0.48f);
// smooth the bandwidth output more aggressively
_center_bandwidth_filter[axis].set_cutoff_frequency(output_rate, output_rate * 0.25f);
// number of cycles to average over, two complete windows to be sure
_noise_calibration_cycles[axis] = (_window_size / _samples_per_frame) * 2;
}
// the number of cycles required to have a proper noise reference
_noise_cycles = (_window_size / _samples_per_frame) * XYZ_AXIS_COUNT;
// calculate harmonic multiplier
uint8_t first_harmonic = 0;
_harmonics = 1; // always search for 1
for (uint8_t i = 0; i < HNF_MAX_HARMONICS; i++) {
if (_ins->get_gyro_harmonic_notch_harmonics() & (1<<i)) {
if (first_harmonic == 0) {
first_harmonic = i + 1;
} else {
_harmonics++;
_harmonic_multiplier = float(i + 1) / first_harmonic;
break;
}
}
}
// finally we are done
_initialized = true;
update_parameters();
// start running FFTs
start_update_thread();
}
// sample the gyros either by using a gyro window sampled at the gyro rate or making invdividual samples
// called from fast_loop thread - anything that requires atomic access to IMU data needs to be done here
void AP_GyroFFT::sample_gyros()
{
if (!analysis_enabled()) {
return;
}
WITH_SEMAPHORE(_sem);
// update counters for gyro window
if (_current_sample_mode == 0) {
// number of available samples are those in the IMU buffer less those we have already consumed
_sample_count = ((_ins->get_raw_gyro_window_index() - _circular_buffer_idx + get_buffer_size()) % get_buffer_size());
if (start_analysis()) {
hal.dsp->fft_start(_state, _ins->get_raw_gyro_window(_update_axis), _circular_buffer_idx, get_buffer_size());
// we have pushed a frame into the FFT loop, move the index to the beginning of the next frame
_circular_buffer_idx = (_circular_buffer_idx + _samples_per_frame) % get_buffer_size();
_sample_count -= _samples_per_frame;
}
}
// for loop rate sampling accumulate and average gyro samples
else {
_oversampled_gyro_accum += _ins->get_raw_gyro();
_oversampled_gyro_count++;
if ((_oversampled_gyro_count % _current_sample_mode) == 0) {
// calculate mean value of accumulated samples
Vector3f sample = _oversampled_gyro_accum / _current_sample_mode;
// fast sampling means that the raw gyro values have already been averaged over 8 samples
_downsampled_gyro_data[0][_downsampled_gyro_idx] = sample.x;
_downsampled_gyro_data[1][_downsampled_gyro_idx] = sample.y;
_downsampled_gyro_data[2][_downsampled_gyro_idx] = sample.z;
_oversampled_gyro_accum.zero();
_oversampled_gyro_count = 0;
_downsampled_gyro_idx = (_downsampled_gyro_idx + 1) % _state->_window_size;
_sample_count++;
if (start_analysis()) {
hal.dsp->fft_start(_state, _downsampled_gyro_data[_update_axis], _circular_buffer_idx, _state->_window_size);
_circular_buffer_idx = (_circular_buffer_idx + _samples_per_frame) % _state->_window_size;
_sample_count -= _samples_per_frame;
}
}
}
_global_state = _thread_state;
}
// analyse gyro data using FFT, returns number of samples still held
// called from FFT thread
uint16_t AP_GyroFFT::update()
{
if (!analysis_enabled()) {
return 0;
}
if (!_sem.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return 0;
}
// only proceeed if a full frame has been pushed into the dsp
if (!_thread_state._analysis_started) {
uint16_t new_sample_count = _sample_count;
_sem.give();
return new_sample_count;
}
uint16_t start_bin = _config._fft_start_bin;
uint16_t end_bin = _config._fft_end_bin;
_sem.give();
// calculate FFT and update filters outside the semaphore
uint16_t bin_max = hal.dsp->fft_analyse(_state, start_bin, end_bin, _harmonics, _config._attenuation_cutoff);
// in order to access _config state we need the semaphore again
WITH_SEMAPHORE(_sem);
// something has been detected, update the peak frequency and associated metrics
update_ref_energy(bin_max);
calculate_noise(bin_max);
// ready to receive another frame
_thread_state._analysis_started = false;
return _sample_count;
}
// whether analysis can be run again or not
bool AP_GyroFFT::start_analysis() {
if (_thread_state._analysis_started) {
return false;
}
if (_sample_count >= _state->_window_size) {
_thread_state._analysis_started = true;
return true;
}
return false;
}
// update calculated values of dynamic parameters - runs at 1Hz
void AP_GyroFFT::update_parameters()
{
if (!_initialized) {
return;
}
WITH_SEMAPHORE(_sem);
// don't allow MAXHZ to go to Nyquist
_fft_max_hz = MIN(_fft_max_hz, _fft_sampling_rate_hz * 0.48);
_config._snr_threshold_db = _snr_threshold_db;
_config._fft_min_hz = _fft_min_hz;
_config._fft_max_hz = _fft_max_hz;
// determine the start FFT bin for all frequency detection
_config._fft_start_bin = MAX(floorf(_fft_min_hz.get() / _state->_bin_resolution), 1);
// determine the endt FFT bin for all frequency detection
_config._fft_end_bin = MIN(ceilf(_fft_max_hz.get() / _state->_bin_resolution), _state->_bin_count);
// actual attenuation from the db value
_config._attenuation_cutoff = powf(10.0f, -_attenuation_power_db / 10.0f);
_config._analysis_enabled = _analysis_enabled;
}
// thread for processing gyro data via FFT
void AP_GyroFFT::update_thread(void)
{
while (true) {
uint16_t remaining_samples = update();
// wait approximately until we are likely to have another frame ready
uint32_t delay = constrain_int32((int32_t(_window_size) - remaining_samples) * 1e6 / _fft_sampling_rate_hz, 0, 100000);
if (delay > 0) {
hal.scheduler->delay_microseconds(delay);
}
}
}
// start the update thread
void AP_GyroFFT::start_update_thread(void)
{
WITH_SEMAPHORE(_sem);
if (_thread_created) {
return;
}
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_GyroFFT::update_thread, void), "apm_fft", FFT_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_IO, 1)) {
AP_HAL::panic("Failed to start AP_GyroFFT update thread");
}
_thread_created = true;
}
// self-test the FFT analyser - can only be done while samples are not being taken
// called from main thread
bool AP_GyroFFT::calibration_check()
{
if (!analysis_enabled()) {
return true;
}
// analysis is started in the main thread, don't trample on in-flight analysis
if (_global_state._analysis_started) {
return true;
}
// still calibrating noise so not ready
if (_global_state._noise_needs_calibration) {
return false;
}
// make sure the frequency maxium is below Nyquist
if (_fft_max_hz > _fft_sampling_rate_hz * 0.5f) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "FFT: config MAXHZ %dHz > %dHz", _fft_max_hz.get(), _fft_sampling_rate_hz / 2);
return false;
}
// larger windows make the the self-test run too long, triggering the watchdog
if (AP_Logger::get_singleton()->log_while_disarmed()
|| _window_size > FFT_DEFAULT_WINDOW_SIZE * 2) {
return true;
}
float max_divergence = self_test_bin_frequencies();
if (max_divergence > _state->_bin_resolution * 0.5f) {
gcs().send_text(MAV_SEVERITY_WARNING, "FFT: self-test FAILED, max error %fHz", max_divergence);
}
return max_divergence <= _state->_bin_resolution * 0.5f;
}
// update the hover frequency input filter. should be called at 100hz when in a stable hover
// called from main thread
void AP_GyroFFT::update_freq_hover(float dt, float throttle_out)
{
if (!analysis_enabled()) {
return;
}
// we have chosen to constrain the hover frequency to be within the range reachable by the third order expo polynomial.
_freq_hover_hz = constrain_float(_freq_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_freq_hz() - _freq_hover_hz), _fft_min_hz, _fft_max_hz);
_bandwidth_hover_hz = constrain_float(_bandwidth_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_bandwidth_hz() - _bandwidth_hover_hz), 0, _fft_max_hz * 0.5f);
_throttle_ref = constrain_float(_throttle_ref + (dt / (10.0f + dt)) * (throttle_out * sq((float)_fft_min_hz.get() / _freq_hover_hz.get()) - _throttle_ref), 0.01f, 0.9f);
}
// save parameters as part of disarming
// called from main thread
void AP_GyroFFT::save_params_on_disarm()
{
if (!analysis_enabled()) {
return;
}
_freq_hover_hz.save();
_bandwidth_hover_hz.save();
_throttle_ref.save();
}
// return an average center frequency weighted by bin energy
// called from main thread
float AP_GyroFFT::get_weighted_noise_center_freq_hz()
{
if (!analysis_enabled()) {
return _fft_min_hz;
}
// there is generally a lot of high-energy, slightly lower frequency noise on yaw, however this
// appears to be a second-order effect as only targetting pitch and roll (x & y) produces much cleaner output all round
if (!_global_state._center_freq_energy.is_nan()
&& !is_zero(_global_state._center_freq_energy.x)
&& !is_zero(_global_state._center_freq_energy.y)) {
return (_global_state._center_freq_hz_filtered.x * _global_state._center_freq_energy.x
+ _global_state._center_freq_hz_filtered.y * _global_state._center_freq_energy.y)
/ (_global_state._center_freq_energy.x + _global_state._center_freq_energy.y);
}
else {
return (_global_state._center_freq_hz_filtered.x + _global_state._center_freq_hz_filtered.y) * 0.5f;
}
}
static const char* LOG_FTN1_NAME = "FTN1";
static const char* LOG_FTN1_LABELS = "TimeUS,PkAvg,PkX,PkY,PkZ,BwAvg,BwX,BwY,BwZ,DnF";
static const char* LOG_FTN1_UNITS = "szzzzzzzzz";
static const char* LOG_FTN1_SCALE = "F---------";
static const char* LOG_FTN1_FORMAT = "Qfffffffff";
static const char* LOG_FTN2_NAME = "FTN2";
static const char* LOG_FTN2_LABELS = "TimeUS,FtX,FtY,FtZ,EnX,EnY,EnZ,SnX,SnY,SnZ,Bin";
static const char* LOG_FTN2_UNITS = "s%%%-------";
static const char* LOG_FTN2_SCALE = "F----------";
static const char* LOG_FTN2_FORMAT = "QfffffffffB";
// log gyro fft messages
void AP_GyroFFT::write_log_messages()
{
if (!analysis_enabled()) {
return;
}
AP::logger().Write(LOG_FTN1_NAME, LOG_FTN1_LABELS, LOG_FTN1_UNITS, LOG_FTN1_SCALE, LOG_FTN1_FORMAT,
AP_HAL::micros64(),
get_weighted_noise_center_freq_hz(),
get_noise_center_freq_hz().x,
get_noise_center_freq_hz().y,
get_noise_center_freq_hz().z,
get_weighted_noise_center_bandwidth_hz(),
get_noise_center_bandwidth_hz().x,
get_noise_center_bandwidth_hz().y,
get_noise_center_bandwidth_hz().z,
_ins->get_gyro_dynamic_notch_center_freq_hz());
AP::logger().Write(LOG_FTN2_NAME, LOG_FTN2_LABELS, LOG_FTN2_UNITS, LOG_FTN2_SCALE, LOG_FTN2_FORMAT,
AP_HAL::micros64(),
get_raw_noise_harmonic_fit().x,
get_raw_noise_harmonic_fit().y,
get_raw_noise_harmonic_fit().z,
get_center_freq_energy().x,
get_center_freq_energy().y,
get_center_freq_energy().z,
get_noise_signal_to_noise_db().x,
get_noise_signal_to_noise_db().y,
get_noise_signal_to_noise_db().z,
get_center_freq_bin().z);
#if DEBUG_FFT
const uint32_t now = AP_HAL::millis();
// output at 1hz
if ((now - _last_output_ms) > 1000) {
// doing this from the update thread overflows the stack
WITH_SEMAPHORE(_sem);
gcs().send_text(MAV_SEVERITY_WARNING, "FFT: f:%.1f, fr:%.1f, b:%u, fd:%.1f",
_debug_state._center_freq_hz_filtered[_update_axis], _debug_state._center_freq_hz[_update_axis], _debug_max_bin, _debug_max_bin_freq);
gcs().send_text(MAV_SEVERITY_WARNING, "FFT: bw:%.1f, e:%.1f, r:%.1f, snr:%.1f",
_debug_state._center_bandwidth_hz[_update_axis], _debug_max_freq_bin, _ref_energy[_update_axis][_debug_max_bin], _debug_snr);
_last_output_ms = now;
}
#endif
}
// return an average noise bandwidth weighted by bin energy
// called from main thread
float AP_GyroFFT::get_weighted_noise_center_bandwidth_hz()
{
if (!analysis_enabled()) {
return 0.0f;
}
if (!_global_state._center_freq_energy.is_nan()
&& !is_zero(_global_state._center_freq_energy.x)
&& !is_zero(_global_state._center_freq_energy.y)) {
return (_global_state._center_bandwidth_hz.x * _global_state._center_freq_energy.x
+ _global_state._center_bandwidth_hz.y * _global_state._center_freq_energy.y)
/ (_global_state._center_freq_energy.x + _global_state._center_freq_energy.y);
}
else {
return (_global_state._center_bandwidth_hz.x + _global_state._center_bandwidth_hz.y) * 0.5f;
}
}
// calculate noise frequencies from FFT data provided by the HAL subsystem
// called from FFT thread
void AP_GyroFFT::calculate_noise(uint16_t max_bin)
{
_thread_state._center_freq_bin[_update_axis] = max_bin;
float weighted_center_freq_hz = 0;
// cacluate the SNR and center frequency energy
const float max_energy = MAX(1.0f, _state->_freq_bins[max_bin]);
const float ref_energy = MAX(1.0f, _ref_energy[_update_axis][max_bin]);
float snr = 10.f * log10f(max_energy) - log10f(ref_energy);
// if the bin energy is above the noise threshold then we have a signal
if (!_thread_state._noise_needs_calibration && !isnan(_state->_freq_bins[max_bin]) && snr > _config._snr_threshold_db) {
// if targetting more than one harmonic then make sure we get the fundamental
// on larger copters the second harmonic often has more energy
const float peak_freq_hz = constrain_float(_state->_max_bin_freq, (float)_config._fft_min_hz, (float)_config._fft_max_hz);
const float second_peak_freq_hz = constrain_float(_state->_second_bin_freq, (float)_config._fft_min_hz, (float)_config._fft_max_hz);
const float harmonic_fit = 100.0f * fabsf(peak_freq_hz - second_peak_freq_hz * _harmonic_multiplier) / peak_freq_hz;
// required fit of 10% is fairly conservative when testing in SITL
if (_harmonics > 1 && peak_freq_hz > second_peak_freq_hz && harmonic_fit < FFT_REQUIRED_HARMONIC_FIT) {
weighted_center_freq_hz = second_peak_freq_hz;
_thread_state._center_freq_energy[_update_axis] = _state->_freq_bins[_state->_second_energy_bin];
_thread_state._center_bandwidth_hz[_update_axis] = _center_bandwidth_filter[_update_axis].apply(_state->_second_noise_width_hz);
} else {
weighted_center_freq_hz = peak_freq_hz;
_thread_state._center_freq_energy[_update_axis] = _state->_freq_bins[max_bin];
_thread_state._center_bandwidth_hz[_update_axis] = _center_bandwidth_filter[_update_axis].apply(_state->_max_noise_width_hz);
}
// record how good the fit was
if (peak_freq_hz > second_peak_freq_hz) {
_thread_state._harmonic_fit[_update_axis] = harmonic_fit;
} else {
_thread_state._harmonic_fit[_update_axis] = 0.0f;
}
_thread_state._center_freq_hz[_update_axis] = weighted_center_freq_hz;
_thread_state._center_snr[_update_axis] = snr;
_missed_cycles = 0;
}
// if we failed to find a signal, carry on using the previous reading
else if (_missed_cycles++ < FFT_MAX_MISSED_UPDATES) {
weighted_center_freq_hz = _thread_state._center_freq_hz[_update_axis];
// Keep the previous center frequency and energy
}
// we failed to find a signal for more than FFT_MAX_MISSED_UPDATES cycles
else {
weighted_center_freq_hz = _config._fft_min_hz;
_thread_state._center_freq_hz[_update_axis] = _config._fft_min_hz;
_thread_state._center_freq_energy[_update_axis] = 0.0f;
_thread_state._center_snr[_update_axis] = 0.0f;
_thread_state._center_bandwidth_hz[_update_axis] = _center_bandwidth_filter[_update_axis].apply(_bandwidth_hover_hz);
}
_thread_state._center_freq_hz_filtered[_update_axis] = _center_freq_filter[_update_axis].apply(weighted_center_freq_hz);
#if DEBUG_FFT
WITH_SEMAPHORE(_sem);
_debug_state = _thread_state;
_debug_max_freq_bin = _state->_freq_bins[max_bin];
_debug_max_bin_freq = _state->_max_bin_freq;
_debug_snr = snr;
_debug_max_bin = max_bin;
#endif
_update_axis = (_update_axis + 1) % XYZ_AXIS_COUNT;
}
// calculate noise baseline from FFT data provided by the HAL subsystem
// called from FFT thread
void AP_GyroFFT::update_ref_energy(uint16_t max_bin)
{
if (!_thread_state._noise_needs_calibration) {
return;
}
// according to https://www.tcd.ie/Physics/research/groups/magnetism/files/lectures/py5021/MagneticSensors3.pdf sensor noise is not necessarily gaussian
// determine a PS noise reference at each of the possble center frequencies
if (_noise_cycles == 0 && _noise_calibration_cycles[_update_axis] > 0) {
for (uint16_t i = 1; i < _state->_bin_count; i++) {
_ref_energy[_update_axis][i] += _state->_freq_bins[i];
}
if (--_noise_calibration_cycles[_update_axis] == 0) {
for (uint16_t i = 1; i < _state->_bin_count; i++) {
const float cycles = (_window_size / _samples_per_frame) * 2;
// overall random noise is reduced by sqrt(N) when averaging periodigrams so adjust for that
_ref_energy[_update_axis][i] = (_ref_energy[_update_axis][i] / cycles) * sqrtf(cycles);
}
_thread_state._noise_needs_calibration &= ~(1 << _update_axis);
}
}
else if (_noise_cycles > 0) {
_noise_cycles--;
}
}
// perform FFT analysis on the range of frequencies supported by the analyser
// called from main thread
float AP_GyroFFT::self_test_bin_frequencies()
{
if (_state->_window_size * sizeof(float) > hal.util->available_memory() / 2) {
gcs().send_text(MAV_SEVERITY_WARNING, "AP_GyroFFT: unable to run self-test, required %u bytes", (unsigned int)(_state->_window_size * sizeof(float)));
return 0.0f;
}
GyroWindow test_window = (float*)hal.util->malloc_type(sizeof(float) * _state->_window_size, DSP_MEM_REGION);
// in the unlikely event we can't allocate a test window, skip the checks
if (test_window == nullptr) {
return 0.0f;
}
float max_divergence = 0;
for (uint16_t bin = _config._fft_start_bin; bin <= _config._fft_end_bin; bin++) {
// the algorithm will only ever return values in this range
float frequency = constrain_float(bin * _state->_bin_resolution, _fft_min_hz, _fft_max_hz);
max_divergence = MAX(max_divergence, self_test(frequency, test_window)); // test bin centers
frequency = constrain_float(bin * _state->_bin_resolution - _state->_bin_resolution / 4, _fft_min_hz, _fft_max_hz);
max_divergence = MAX(max_divergence, self_test(frequency, test_window)); // test bin off-centers
}
hal.util->free_type(test_window, sizeof(float) * _window_size, DSP_MEM_REGION);
return max_divergence;
}
// perform FFT analysis of a single sine wave at the selected frequency
// called from main thread
float AP_GyroFFT::self_test(float frequency, GyroWindow test_window)
{
for(uint16_t i = 0; i < _state->_window_size; i++) {
test_window[i]= sinf(2.0f * M_PI * frequency * i / _fft_sampling_rate_hz) * ToRad(20) * 2000;
}
_update_axis = 0;
hal.dsp->fft_start(_state, test_window, 0, _state->_window_size);
uint16_t max_bin = hal.dsp->fft_analyse(_state, _config._fft_start_bin, _config._fft_end_bin, _harmonics, _config._attenuation_cutoff);
if (max_bin <= 0) {
gcs().send_text(MAV_SEVERITY_WARNING, "FFT: self-test failed, failed to find frequency %f", frequency);
}
calculate_noise(max_bin);
float max_divergence = 0;
// make sure the selected frequencies are in the right bin
max_divergence = MAX(max_divergence, fabsf(frequency - _thread_state._center_freq_hz[0]));
if (_thread_state._center_freq_hz[0] < (frequency - _state->_bin_resolution * 0.5f) || _thread_state._center_freq_hz[0] > (frequency + _state->_bin_resolution * 0.5f)) {
gcs().send_text(MAV_SEVERITY_WARNING, "FFT: self-test failed: wanted %f, had %f", frequency, _thread_state._center_freq_hz[0]);
}
#if DEBUG_FFT
else {
gcs().send_text(MAV_SEVERITY_INFO, "FFT: self-test succeeded: wanted %f, had %f", frequency, _thread_state._center_freq_hz[0]);
}
#endif
return max_divergence;
}
// singleton instance
AP_GyroFFT *AP_GyroFFT::_singleton;
namespace AP {
AP_GyroFFT *fft()
{
return AP_GyroFFT::get_singleton();
}
}
#endif // HAL_GYROFFT_ENABLED

View File

@ -0,0 +1,246 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Code by Andy Piper
*/
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#ifndef HAL_GYROFFT_ENABLED
#define HAL_GYROFFT_ENABLED HAL_WITH_DSP
#endif
#if HAL_GYROFFT_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <Filter/LowPassFilter.h>
#define DEBUG_FFT 0
// a library that leverages the HAL DSP support to perform FFT analysis on gyro samples
class AP_GyroFFT
{
public:
AP_GyroFFT();
// Do not allow copies
AP_GyroFFT(const AP_GyroFFT &other) = delete;
AP_GyroFFT &operator=(const AP_GyroFFT&) = delete;
void init(uint32_t target_looptime);
// cycle through the FFT steps - runs at 400Hz
uint16_t update();
// capture gyro values at the appropriate update rate - runs at fast loop rate
void sample_gyros();
// update calculated values of dynamic parameters - runs at 1Hz
void update_parameters();
// thread for processing gyro data via FFT
void update_thread();
// start the update thread
void start_update_thread();
// check at startup that standard frequencies can be detected
bool calibration_check();
// called when hovering to determine the average peak frequency and reference value
void update_freq_hover(float dt, float throttle_out);
// called to save the average peak frequency and reference value
void save_params_on_disarm();
// dynamically enable or disable the analysis through the aux switch
void set_analysis_enabled(bool enabled) { _analysis_enabled = enabled; };
// detected peak frequency filtered at 1/3 the update rate
Vector3f get_noise_center_freq_hz() const { return _global_state._center_freq_hz_filtered; }
// energy of the background noise at the detected center frequency
Vector3f get_noise_signal_to_noise_db() const { return _global_state._center_snr; }
// detected peak frequency weighted by energy
float get_weighted_noise_center_freq_hz();
// detected peak frequency
Vector3f get_raw_noise_center_freq_hz() const { return _global_state._center_freq_hz; }
// match between first and second harmonics
Vector3f get_raw_noise_harmonic_fit() const { return _global_state._harmonic_fit; }
// energy of the detected peak frequency
Vector3f get_center_freq_energy() const { return _global_state._center_freq_energy; }
// index of the FFT bin containing the detected peak frequency
Vector3<uint16_t> get_center_freq_bin() const { return _global_state._center_freq_bin; }
// detected peak bandwidth
Vector3f get_noise_center_bandwidth_hz() const { return _global_state._center_bandwidth_hz; };
// weighted detected peak bandwidth
float get_weighted_noise_center_bandwidth_hz();
// log gyro fft messages
void write_log_messages();
static const struct AP_Param::GroupInfo var_info[];
static AP_GyroFFT *get_singleton() { return _singleton; }
private:
// calculate the peak noise frequency
void calculate_noise(uint16_t max_bin);
// update the estimation of the background noise energy
void update_ref_energy(uint16_t max_bin);
// test frequency detection for all of the allowable bins
float self_test_bin_frequencies();
// detect the provided frequency
float self_test(float frequency, GyroWindow test_window);
// whether to run analysis or not
bool analysis_enabled() const { return _initialized && _analysis_enabled && _thread_created; };
// whether analysis can be run again or not
bool start_analysis();
// the size of the ring buffer in both the IMU backend
uint16_t get_buffer_size() const { return _state->_window_size + INS_MAX_GYRO_WINDOW_SAMPLES; }
// semaphore for access to shared FFT data
HAL_Semaphore _sem;
// data accessible from the main thread protected by the semaphore
struct EngineState {
// energy of the detected peak frequency
Vector3f _center_freq_energy;
// energy of the detected peak frequency in dB
Vector3f _center_freq_energy_db;
// detected peak frequency
Vector3f _center_freq_hz;
// fit between first and second harmonics
Vector3f _harmonic_fit;
// bin of detected poeak frequency
Vector3<uint16_t> _center_freq_bin;
// filtered version of the peak frequency
Vector3f _center_freq_hz_filtered;
// signal to noise ratio of PSD at the detected centre frequency
Vector3f _center_snr;
// detected peak width
Vector3f _center_bandwidth_hz;
// axes that still require noise calibration
uint8_t _noise_needs_calibration : 3;
// whether the analyzer is mid-cycle
bool _analysis_started = false;
};
// Shared FFT engine state local to the FFT thread
EngineState _thread_state;
// Shared FFT engine state accessible by the main thread
EngineState _global_state;
// configuration data local to the FFT thread but set from the main thread
struct EngineConfig {
// whether the analyzer should be run
bool _analysis_enabled;
// minimum frequency of the detection window
uint16_t _fft_min_hz;
// maximum frequency of the detection window
uint16_t _fft_max_hz;
// configured start bin based on min hz
uint16_t _fft_start_bin;
// configured end bin based on max hz
uint16_t _fft_end_bin;
// attenuation cutoff for calculation of hover bandwidth
float _attenuation_cutoff;
// SNR Threshold
float _snr_threshold_db;
} _config;
// number of sampeles needed before a new frame can be processed
uint16_t _samples_per_frame;
// downsampled gyro data circular buffer index frequency analysis
uint16_t _circular_buffer_idx;
// number of collected unprocessed gyro samples
uint16_t _sample_count;
// downsampled gyro data circular buffer for frequency analysis
float* _downsampled_gyro_data[XYZ_AXIS_COUNT];
// accumulator for sampled gyro data
Vector3f _oversampled_gyro_accum;
// count of oversamples
uint16_t _oversampled_gyro_count;
// current write index in the buffer
uint16_t _downsampled_gyro_idx;
// state of the FFT engine
AP_HAL::DSP::FFTWindowState* _state;
// update state machine step information
uint8_t _update_axis;
// noise base of the gyros
Vector3f* _ref_energy;
// the number of cycles required to have a proper noise reference
uint16_t _noise_cycles;
// number of cycles over which to generate noise ensemble averages
uint16_t _noise_calibration_cycles[XYZ_AXIS_COUNT];
// current _sample_mode
uint8_t _current_sample_mode : 3;
// harmonic multiplier for two highest peaks
float _harmonic_multiplier;
// searched harmonics - inferred from harmonic notch harmoncis
uint8_t _harmonics;
// smoothing filter on the output
LowPassFilterFloat _center_freq_filter[XYZ_AXIS_COUNT];
// smoothing filter on the bandwidth
LowPassFilterFloat _center_bandwidth_filter[XYZ_AXIS_COUNT];
// configured sampling rate
uint16_t _fft_sampling_rate_hz;
// number of cycles without a detected signal
uint8_t _missed_cycles;
// whether the analyzer initialized correctly
bool _initialized;
// whether the analyzer should be run
bool _analysis_enabled = true;
// whether the update thread was created
bool _thread_created = false;
// minimum frequency of the detection window
AP_Int16 _fft_min_hz;
// maximum frequency of the detection window
AP_Int16 _fft_max_hz;
// size of the FFT window
AP_Int16 _window_size;
// percentage overlap of FFT windows
AP_Float _window_overlap;
// overall enablement of the feature
AP_Int8 _enable;
// gyro rate sampling or cycle divider
AP_Int8 _sample_mode;
// learned throttle reference for the hover frequency
AP_Float _throttle_ref;
// learned hover filter frequency
AP_Float _freq_hover_hz;
// SNR Threshold
AP_Float _snr_threshold_db;
// attenuation to use for calculating the peak bandwidth at hover
AP_Float _attenuation_power_db;
// learned peak bandwidth at configured attenuation at hover
AP_Float _bandwidth_hover_hz;
AP_InertialSensor* _ins;
#if DEBUG_FFT
uint32_t _last_output_ms;
EngineState _debug_state;
float _debug_max_bin_freq;
float _debug_max_freq_bin;
uint16_t _debug_max_bin;
float _debug_snr;
#endif
static AP_GyroFFT *_singleton;
};
namespace AP {
AP_GyroFFT *fft();
};
#endif // HAL_GYROFFT_ENABLED

View File

@ -0,0 +1,201 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "{}"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright {yyyy} {name of copyright owner}
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

View File

@ -0,0 +1,145 @@
# CMSIS Version 5 - ArduPilot
This directory contains the pre-built CMSIS v5.6.0 (master branch) DSP libraries and headers for Arm Cortex chips taken from github.
The CMSIS 5 repository is very large (400Mb) so we only copy the pieces that we need for building ArduPilot.
The CMSIS 5 README follows.
# CMSIS Version 5
The branch *master* of this GitHub repository contains the CMSIS Version 5.6.0. The [documentation](http://arm-software.github.io/CMSIS_5/General/html/index.html) is available under http://arm-software.github.io/CMSIS_5/General/html/index.html
Use [Issues](https://github.com/ARM-software/CMSIS_5#issues-and-labels) to provide feedback and report problems for CMSIS Version 5.
**Note:** The branch *develop* of this GitHub repository reflects our current state of development and is constantly updated. It gives our users and partners contiguous access to the CMSIS development. It allows you to review the work and provide feedback or create pull requests for contributions.
A [pre-built documentation](http://www.keil.com/pack/doc/CMSIS_Dev/index.html) is updated from time to time, but may be also generated using the instructions under [Generate CMSIS Pack for Release](https://github.com/ARM-software/CMSIS_5#generate-cmsis-pack-for-release).
## Overview of CMSIS Components
The following is an list of all CMSIS components that are available.
| CMSIS-... | Target Processors | Description |
|:----------|:--------------------|:-------------|
|[Core(M)](http://arm-software.github.io/CMSIS_5/Core/html/index.html) | All Cortex-M, SecurCore | Standardized API for the Cortex-M processor core and peripherals. Includes intrinsic functions for Cortex-M4/M7/M33/M35P SIMD instructions.|
|[Core(A)](http://arm-software.github.io/CMSIS_5/Core_A/html/index.html)| Cortex-A5/A7/A9 | API and basic run-time system for the Cortex-A5/A7/A9 processor core and peripherals.|
|[Driver](http://arm-software.github.io/CMSIS_5/Driver/html/index.html) | All Cortex-M, SecurCore | Generic peripheral driver interfaces for middleware. Connects microcontroller peripherals with middleware that implements for example communication stacks, file systems, or graphic user interfaces.|
|[DSP](http://arm-software.github.io/CMSIS_5/DSP/html/index.html) | All Cortex-M | DSP library collection with over 60 Functions for various data types: fixed-point (fractional q7, q15, q31) and single precision floating-point (32-bit). Implementations optimized for the SIMD instruction set are available for Cortex-M4/M7/M33/M35P.|
|[NN](http://arm-software.github.io/CMSIS_5/NN/html/index.html) | All Cortex-M | Collection of efficient neural network kernels developed to maximize the performance and minimize the memory footprint on Cortex-M processor cores.|
|[RTOS v1](http://arm-software.github.io/CMSIS_5/RTOS/html/index.html) | Cortex-M0/M0+/M3/M4/M7 | Common API for real-time operating systems along with a reference implementation based on RTX. It enables software components that can work across multiple RTOS systems.|
|[RTOS v2](http://arm-software.github.io/CMSIS_5/RTOS2/html/index.html)| All Cortex-M, Cortex-A5/A7/A9 | Extends CMSIS-RTOS v1 with Armv8-M support, dynamic object creation, provisions for multi-core systems, binary compatible interface. |
|[Pack](http://arm-software.github.io/CMSIS_5/Pack/html/index.html) | All Cortex-M, SecurCore, Cortex-A5/A7/A9 | Describes a delivery mechanism for software components, device parameters, and evaluation board support. It simplifies software re-use and product life-cycle management (PLM). |
|[SVD](http://arm-software.github.io/CMSIS_5/SVD/html/index.html) | All Cortex-M, SecurCore | Peripheral description of a device that can be used to create peripheral awareness in debuggers or CMSIS-Core header files.|
|[DAP](http://arm-software.github.io/CMSIS_5/DAP/html/index.html) | All Cortex | Firmware for a debug unit that interfaces to the CoreSight Debug Access Port. |
|[Zone](http://arm-software.github.io/CMSIS_5/Zone/html/index.html) | All Cortex | Defines methods to describe system resources and to partition these resources into multiple projects and execution areas. |
## Implemented Enhancements
- CMSIS-Core-A, RTX5: implementation for Cortex-A5/A7/A9
- Support for Armv8-M Architecture (Mainline and Baseline) as well as devices Cortex-M23 and Cortex-M33
- CMSIS-RTOS2: RTX 5 is now available for IAR, GCC, Arm Compiler 5, Arm Compiler 6
- CMSIS-RTOS2: FreeRTOS adoption (release) is available https://github.com/ARM-software/CMSIS-FreeRTOS
- CMSIS-NN: Bare metal Neural Network function library.
- CMSIS-DAP v2: with WinUSB for faster communication and separate pipe for SWO support
- Config Wizard extension: access enums for configuration information
## Further Planned Enhancements
- CMSIS-Zone: management of complex system
- CMSIS-Pack:
- System Description SDF Format: describe more complex debug topologies than with a Debug Description in a tool agnostic way
- Github based workflow: allows to develop software packs using github infra-structure
- Flash algorithm via debugger: Some TurstZone enable devices cannot execute RAM. Commands that allow flash programming will be added to Debug Description.
- CPDSC project file format: allows project templates that are agnostic of an IDE
- Minimize need for IDE specific settings: CMSIS-Pack supports IDE specific parameters. Analyze and minimize
For further details see also the [Slides of the Embedded World CMSIS Partner Meeting](https://github.com/ARM-software/CMSIS_5/blob/develop/CMSIS_EW2019.pdf).
## Other related GitHub repositories
| Repository | Description |
|:--------------------------- |:--------------------------------------------------------- |
| [cmsis-pack-eclipse](https://github.com/ARM-software/cmsis-pack-eclipse) | CMSIS-Pack Management for Eclipse reference implementation Pack support |
| [CMSIS-FreeRTOS](https://github.com/arm-software/CMSIS-FreeRTOS) | CMSIS-RTOS adoption of FreeRTOS |
| [CMSIS-Driver](https://github.com/arm-software/CMSIS-Driver) | Generic MCU driver implementations and templates for Ethernet MAC/PHY and Flash. |
| [CMSIS-Driver_Validation](https://github.com/ARM-software/CMSIS-Driver_Validation) | CMSIS-Driver Validation can be used to verify CMSIS-Driver in a user system |
| [CMSIS-Zone](https://github.com/ARM-software/CMSIS-Zone) | CMSIS-Zone Utility along with example projects and FreeMarker templates |
| [NXP_LPC](https://github.com/ARM-software/NXP_LPC) | CMSIS Driver Implementations for the NXP LPC Microcontroller Series |
| [mdk-packs](https://github.com/mdk-packs) | IoT cloud connectors as trail implementations for MDK (help us to make it generic)|
| [trustedfirmware.org](https://www.trustedfirmware.org/) | Arm Trusted Firmware provides a reference implementation of secure world software for Armv8-A and Armv8-M.|
## Directory Structure
| Directory | Content |
|:-------------------- |:--------------------------------------------------------- |
| CMSIS/Core | CMSIS-Core(M) related files (for release) |
| CMSIS/Core_A | CMSIS-Core(A) related files (for release) |
| CMSIS/CoreValidation | Validation for Core(M) and Core(A) (NOT part of release) |
| CMSIS/DAP | CMSIS-DAP related files and examples |
| CMSIS/Driver | CMSIS-Driver API headers and template files |
| CMSIS/DSP | CMSIS-DSP related files |
| CMSIS/NN | CMSIS-NN related files |
| CMSIS/RTOS | RTOS v1 related files (for Cortex-M) |
| CMSIS/RTOS2 | RTOS v2 related files (for Cortex-M & Armv8-M) |
| CMSIS/Pack | CMSIS-Pack examples and tutorials |
| CMSIS/DoxyGen | Source of the documentation |
| CMSIS/Utilities | Utility programs |
## Generate CMSIS Pack for Release
This GitHub development repository contains already pre-built libraries (stored in Git-LFS) of various software components (DSP, RTOS, RTOS2).
These libraries are validated for release. Git-LFS needs to be installed to retrieve the actual binary files, please see https://git-lfs.github.com/.
To build a complete CMSIS pack for installation the following additional tools are required:
- **doxygen.exe** Version: 1.8.6 (Documentation Generator)
- **mscgen.exe** Version: 0.20 (Message Sequence Chart Converter)
- **7z.exe (7-Zip)** Version: 16.02 (File Archiver)
Using these tools, you can generate on a Windows PC:
- **CMSIS Software Pack** using the batch file **gen_pack.bat** (located in ./CMSIS/Utilities). This batch file also generates the documentation.
- **CMSIS Documentation** using the batch file **genDoc.bat** (located in ./CMSIS/Doxygen).
The file ./CMSIS/DoxyGen/How2Doc.txt describes the rules for creating API documentation.
## License
Arm CMSIS is licensed under Apache-2.0.
## Contributions and Pull Requests
Contributions are accepted under Apache-2.0. Only submit contributions where you have authored all of the code.
### Issues and Labels
Please feel free to raise an [issue on GitHub](https://github.com/ARM-software/CMSIS_5/issues)
to report misbehavior (i.e. bugs) or start discussions about enhancements. This
is your best way to interact directly with the maintenance team and the community.
We encourage you to append implementation suggestions as this helps to decrease the
workload of the very limited maintenance team.
We will be monitoring and responding to issues as best we can.
Please attempt to avoid filing duplicates of open or closed items when possible.
In the spirit of openness we will be tagging issues with the following:
- **bug** We consider this issue to be a bug that will be investigated.
- **wontfix** - We appreciate this issue but decided not to change the current behavior.
- **enhancement** Denotes something that will be implemented soon.
- **future** - Denotes something not yet schedule for implementation.
- **out-of-scope** - We consider this issue loosely related to CMSIS. It might by implemented outside of CMSIS. Let us know about your work.
- **question** We have further questions to this issue. Please review and provide feedback.
- **documentation** - This issue is a documentation flaw that will be improved in future.
- **review** - This issue is under review. Please be patient.
- **DONE** - We consider this issue as resolved - please review and close it. In case of no further activity this issues will be closed after a week.
- **duplicate** - This issue is already addressed elsewhere, see comment with provided references.
- **Important Information** - We provide essential informations regarding planned or resolved major enhancements.

View File

@ -0,0 +1,378 @@
/* ----------------------------------------------------------------------
* Project: CMSIS DSP Library
* Title: arm_common_tables.h
* Description: Extern declaration for common tables
*
* $Date: 27. January 2017
* $Revision: V.1.5.1
*
* Target Processor: Cortex-M cores
* -------------------------------------------------------------------- */
/*
* Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef _ARM_COMMON_TABLES_H
#define _ARM_COMMON_TABLES_H
#include "arm_math.h"
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES)
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREV_1024)
extern const uint16_t armBitRevTable[1024];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_16)
extern const float32_t twiddleCoef_16[32];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_32)
extern const float32_t twiddleCoef_32[64];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_64)
extern const float32_t twiddleCoef_64[128];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_128)
extern const float32_t twiddleCoef_128[256];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_256)
extern const float32_t twiddleCoef_256[512];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_512)
extern const float32_t twiddleCoef_512[1024];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_1024)
extern const float32_t twiddleCoef_1024[2048];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_2048)
extern const float32_t twiddleCoef_2048[4096];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_4096)
extern const float32_t twiddleCoef_4096[8192];
#define twiddleCoef twiddleCoef_4096
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_16)
extern const q31_t twiddleCoef_16_q31[24];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_32)
extern const q31_t twiddleCoef_32_q31[48];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_64)
extern const q31_t twiddleCoef_64_q31[96];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_128)
extern const q31_t twiddleCoef_128_q31[192];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_256)
extern const q31_t twiddleCoef_256_q31[384];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_512)
extern const q31_t twiddleCoef_512_q31[768];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_1024)
extern const q31_t twiddleCoef_1024_q31[1536];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_2048)
extern const q31_t twiddleCoef_2048_q31[3072];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_4096)
extern const q31_t twiddleCoef_4096_q31[6144];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_16)
extern const q15_t twiddleCoef_16_q15[24];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_32)
extern const q15_t twiddleCoef_32_q15[48];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_64)
extern const q15_t twiddleCoef_64_q15[96];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_128)
extern const q15_t twiddleCoef_128_q15[192];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_256)
extern const q15_t twiddleCoef_256_q15[384];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_512)
extern const q15_t twiddleCoef_512_q15[768];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_1024)
extern const q15_t twiddleCoef_1024_q15[1536];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_2048)
extern const q15_t twiddleCoef_2048_q15[3072];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_4096)
extern const q15_t twiddleCoef_4096_q15[6144];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_32)
extern const float32_t twiddleCoef_rfft_32[32];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_64)
extern const float32_t twiddleCoef_rfft_64[64];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_128)
extern const float32_t twiddleCoef_rfft_128[128];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_256)
extern const float32_t twiddleCoef_rfft_256[256];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_512)
extern const float32_t twiddleCoef_rfft_512[512];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_1024)
extern const float32_t twiddleCoef_rfft_1024[1024];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_2048)
extern const float32_t twiddleCoef_rfft_2048[2048];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_4096)
extern const float32_t twiddleCoef_rfft_4096[4096];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
/* floating-point bit reversal tables */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_16)
#define ARMBITREVINDEXTABLE_16_TABLE_LENGTH ((uint16_t)20)
extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE_16_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_32)
#define ARMBITREVINDEXTABLE_32_TABLE_LENGTH ((uint16_t)48)
extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE_32_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_64)
#define ARMBITREVINDEXTABLE_64_TABLE_LENGTH ((uint16_t)56)
extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE_64_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_128)
#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208)
extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_256)
#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440)
extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_512)
#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448)
extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_1024)
#define ARMBITREVINDEXTABLE_1024_TABLE_LENGTH ((uint16_t)1800)
extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE_1024_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_2048)
#define ARMBITREVINDEXTABLE_2048_TABLE_LENGTH ((uint16_t)3808)
extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE_2048_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_4096)
#define ARMBITREVINDEXTABLE_4096_TABLE_LENGTH ((uint16_t)4032)
extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE_4096_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
/* fixed-point bit reversal tables */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_16)
#define ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH ((uint16_t)12)
extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_32)
#define ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH ((uint16_t)24)
extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_64)
#define ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH ((uint16_t)56)
extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_128)
#define ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH ((uint16_t)112)
extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_256)
#define ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH ((uint16_t)240)
extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_512)
#define ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH ((uint16_t)480)
extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_1024)
#define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992)
extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_2048)
#define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984)
extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_4096)
#define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032)
extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_F32)
extern const float32_t realCoefA[8192];
extern const float32_t realCoefB[8192];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q31)
extern const q31_t realCoefAQ31[8192];
extern const q31_t realCoefBQ31[8192];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q15)
extern const q15_t realCoefAQ15[8192];
extern const q15_t realCoefBQ15[8192];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_128)
extern const float32_t Weights_128[256];
extern const float32_t cos_factors_128[128];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_512)
extern const float32_t Weights_512[1024];
extern const float32_t cos_factors_512[512];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_2048)
extern const float32_t Weights_2048[4096];
extern const float32_t cos_factors_2048[2048];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_8192)
extern const float32_t Weights_8192[16384];
extern const float32_t cos_factors_8192[8192];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_128)
extern const q15_t WeightsQ15_128[256];
extern const q15_t cos_factorsQ15_128[128];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_512)
extern const q15_t WeightsQ15_512[1024];
extern const q15_t cos_factorsQ15_512[512];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_2048)
extern const q15_t WeightsQ15_2048[4096];
extern const q15_t cos_factorsQ15_2048[2048];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_8192)
extern const q15_t WeightsQ15_8192[16384];
extern const q15_t cos_factorsQ15_8192[8192];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_128)
extern const q31_t WeightsQ31_128[256];
extern const q31_t cos_factorsQ31_128[128];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_512)
extern const q31_t WeightsQ31_512[1024];
extern const q31_t cos_factorsQ31_512[512];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_2048)
extern const q31_t WeightsQ31_2048[4096];
extern const q31_t cos_factorsQ31_2048[2048];
#endif
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_8192)
extern const q31_t WeightsQ31_8192[16384];
extern const q31_t cos_factorsQ31_8192[8192];
#endif
#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_ALLOW_TABLES)
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q15)
extern const q15_t armRecipTableQ15[64];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q31)
extern const q31_t armRecipTableQ31[64];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */
/* Tables for Fast Math Sine and Cosine */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_F32)
extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q31)
extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */
#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q15)
extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1];
#endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */
#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_TABLES) */
#endif /* ARM_COMMON_TABLES_H */

View File

@ -0,0 +1,66 @@
/* ----------------------------------------------------------------------
* Project: CMSIS DSP Library
* Title: arm_const_structs.h
* Description: Constant structs that are initialized for user convenience.
* For example, some can be given as arguments to the arm_cfft_f32() function.
*
* $Date: 27. January 2017
* $Revision: V.1.5.1
*
* Target Processor: Cortex-M cores
* -------------------------------------------------------------------- */
/*
* Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef _ARM_CONST_STRUCTS_H
#define _ARM_CONST_STRUCTS_H
#include "arm_math.h"
#include "arm_common_tables.h"
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096;
#endif

File diff suppressed because it is too large Load Diff