Browse Source
- this is a work in progress experiment to compute real time FFTs from raw gyro FIFO data on Cortex-m hardware (stm32f4/f7/h7, etc)sbg
Daniel Agar
4 years ago
committed by
GitHub
16 changed files with 832 additions and 0 deletions
@ -0,0 +1,15 @@
@@ -0,0 +1,15 @@
|
||||
uint64 timestamp # time since system start (microseconds) |
||||
uint64 timestamp_sample |
||||
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles |
||||
|
||||
float32 dt # delta time between samples (microseconds) |
||||
float32 scale |
||||
|
||||
uint8 samples # number of valid samples |
||||
|
||||
uint8 peak_index |
||||
|
||||
float32 peak_frequency_0 |
||||
float32 peak_frequency_1 |
||||
float32 peak_frequency_2 |
@ -0,0 +1,23 @@
@@ -0,0 +1,23 @@
|
||||
uint64 timestamp # time since system start (microseconds) |
||||
uint64 timestamp_sample |
||||
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles |
||||
|
||||
float32 dt # delta time between samples (microseconds) |
||||
|
||||
uint16 samples # number of valid samples |
||||
|
||||
float32 resolution_hz |
||||
|
||||
int16[128] fft |
||||
|
||||
uint16 peak_index |
||||
uint16 peak_index_quinns |
||||
|
||||
float32 peak_frequency |
||||
float32 peak_frequency_quinns |
||||
|
||||
uint8 AXIS_X = 0 |
||||
uint8 AXIS_Y = 1 |
||||
uint8 AXIS_Z = 2 |
||||
uint8 axis |
@ -0,0 +1,44 @@
@@ -0,0 +1,44 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name PX4 nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_module( |
||||
MODULE modules__fake_gyro |
||||
MAIN fake_gyro |
||||
COMPILE_FLAGS |
||||
${MAX_CUSTOM_OPT_LEVEL} |
||||
SRCS |
||||
FakeGyro.cpp |
||||
FakeGyro.hpp |
||||
DEPENDS |
||||
px4_work_queue |
||||
) |
@ -0,0 +1,132 @@
@@ -0,0 +1,132 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "FakeGyro.hpp" |
||||
|
||||
using namespace time_literals; |
||||
|
||||
FakeGyro::FakeGyro() : |
||||
ModuleParams(nullptr), |
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default) |
||||
{ |
||||
} |
||||
|
||||
bool FakeGyro::init() |
||||
{ |
||||
ScheduleOnInterval(SENSOR_RATE, SENSOR_RATE); |
||||
return true; |
||||
} |
||||
|
||||
void FakeGyro::Run() |
||||
{ |
||||
if (should_exit()) { |
||||
ScheduleClear(); |
||||
exit_and_cleanup(); |
||||
return; |
||||
} |
||||
|
||||
sensor_gyro_fifo_s sensor_gyro_fifo{}; |
||||
sensor_gyro_fifo.timestamp_sample = hrt_absolute_time(); |
||||
sensor_gyro_fifo.device_id = 1; |
||||
sensor_gyro_fifo.samples = GYRO_RATE / (1e6f / SENSOR_RATE); |
||||
sensor_gyro_fifo.dt = 1e6f / GYRO_RATE; // 8 kHz fake gyro
|
||||
sensor_gyro_fifo.scale = math::radians(2000.f) / static_cast<float>(INT16_MAX - 1); // 2000 degrees/second max
|
||||
|
||||
const float dt_s = sensor_gyro_fifo.dt / 1e6f; |
||||
const float x_freq = 15.f; // 15 Hz x frequency
|
||||
const float y_freq = 63.5f; // 63.5 Hz y frequency
|
||||
const float z_freq = 99.f; // 99 Hz z frequency
|
||||
|
||||
for (int n = 0; n < sensor_gyro_fifo.samples; n++) { |
||||
_time += dt_s; |
||||
const float k = 2.f * M_PI_F * _time; |
||||
|
||||
sensor_gyro_fifo.x[n] = (INT16_MAX - 1) * sinf(k * x_freq); |
||||
sensor_gyro_fifo.y[n] = (INT16_MAX - 1) / 2 * sinf(k * y_freq); |
||||
sensor_gyro_fifo.z[n] = (INT16_MAX - 1) * cosf(k * z_freq); |
||||
} |
||||
|
||||
sensor_gyro_fifo.timestamp = hrt_absolute_time(); |
||||
_sensor_gyro_fifo_pub.publish(sensor_gyro_fifo); |
||||
} |
||||
|
||||
int FakeGyro::task_spawn(int argc, char *argv[]) |
||||
{ |
||||
FakeGyro *instance = new FakeGyro(); |
||||
|
||||
if (instance) { |
||||
_object.store(instance); |
||||
_task_id = task_id_is_work_queue; |
||||
|
||||
if (instance->init()) { |
||||
return PX4_OK; |
||||
} |
||||
|
||||
} else { |
||||
PX4_ERR("alloc failed"); |
||||
} |
||||
|
||||
delete instance; |
||||
_object.store(nullptr); |
||||
_task_id = -1; |
||||
|
||||
return PX4_ERROR; |
||||
} |
||||
|
||||
int FakeGyro::custom_command(int argc, char *argv[]) |
||||
{ |
||||
return print_usage("unknown command"); |
||||
} |
||||
|
||||
int FakeGyro::print_usage(const char *reason) |
||||
{ |
||||
if (reason) { |
||||
PX4_WARN("%s\n", reason); |
||||
} |
||||
|
||||
PRINT_MODULE_DESCRIPTION( |
||||
R"DESCR_STR( |
||||
### Description |
||||
|
||||
)DESCR_STR"); |
||||
|
||||
PRINT_MODULE_USAGE_NAME("fake_gyro", "driver"); |
||||
PRINT_MODULE_USAGE_COMMAND("start"); |
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); |
||||
return 0; |
||||
} |
||||
|
||||
extern "C" __EXPORT int fake_gyro_main(int argc, char *argv[]) |
||||
{ |
||||
return FakeGyro::main(argc, argv); |
||||
} |
@ -0,0 +1,71 @@
@@ -0,0 +1,71 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <px4_platform_common/defines.h> |
||||
#include <px4_platform_common/module.h> |
||||
#include <px4_platform_common/module_params.h> |
||||
#include <px4_platform_common/posix.h> |
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> |
||||
#include <uORB/PublicationMulti.hpp> |
||||
#include <uORB/Subscription.hpp> |
||||
#include <uORB/topics/sensor_gyro_fifo.h> |
||||
|
||||
class FakeGyro : public ModuleBase<FakeGyro>, public ModuleParams, public px4::ScheduledWorkItem |
||||
{ |
||||
public: |
||||
FakeGyro(); |
||||
~FakeGyro() override = default; |
||||
|
||||
/** @see ModuleBase */ |
||||
static int task_spawn(int argc, char *argv[]); |
||||
|
||||
/** @see ModuleBase */ |
||||
static int custom_command(int argc, char *argv[]); |
||||
|
||||
/** @see ModuleBase */ |
||||
static int print_usage(const char *reason = nullptr); |
||||
|
||||
bool init(); |
||||
|
||||
private: |
||||
static constexpr uint32_t SENSOR_RATE = 1250; |
||||
static constexpr float GYRO_RATE = 8000; |
||||
|
||||
void Run() override; |
||||
|
||||
uORB::PublicationMulti<sensor_gyro_fifo_s> _sensor_gyro_fifo_pub{ORB_ID(sensor_gyro_fifo)}; |
||||
|
||||
float _time{0.f}; |
||||
}; |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
Subproject commit 03a697980f808120f1b75bfe0a96c2dd31bafbbc |
@ -0,0 +1,107 @@
@@ -0,0 +1,107 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name PX4 nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
|
||||
px4_add_git_submodule(TARGET git_cmsis_v5 PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMSIS_5") |
||||
|
||||
# Needed to include the configBoot module |
||||
# Define the path to CMSIS-DSP (ROOT is defined on command line when using cmake) |
||||
set(ROOT ${CMAKE_CURRENT_SOURCE_DIR}/CMSIS_5) |
||||
set(DSP ${ROOT}/CMSIS/DSP) |
||||
|
||||
set(GCC ON CACHE BOOL "") |
||||
set(PLATFORM "FVP" CACHE STRING "") |
||||
set(ARM_CPU ${ARCHITECTURE} CACHE STRING "Set ARM CPU. Default : cortex-m4") |
||||
|
||||
set(FASTMATH ON CACHE BOOL "") |
||||
set(TRANSFORM ON CACHE BOOL "") |
||||
#set(CONFIGTABLE ON CACHE BOOL "") |
||||
#set(ALLFAST ON CACHE BOOL "") |
||||
#set(ALLFFT ON CACHE BOOL "") |
||||
|
||||
add_compile_options( |
||||
#-Wno-strict-prototypes |
||||
-Wno-error |
||||
|
||||
-DARM_FFT_ALLOW_TABLES |
||||
|
||||
-DARM_ALL_FFT_TABLES |
||||
-DARM_TABLE_TWIDDLECOEF_Q15_128 |
||||
-DARM_TABLE_BITREVIDX_FXT_128 |
||||
-DARM_TABLE_REALCOEF_Q15 |
||||
|
||||
-DARMCM4_FP |
||||
-DARM_MATH_LOOPUNROLL |
||||
-DCORTEXM |
||||
) |
||||
|
||||
add_compile_options($<$<COMPILE_LANGUAGE:C>:-Wno-nested-externs>) |
||||
|
||||
px4_add_module( |
||||
MODULE modules__gyro_fft |
||||
MAIN gyro_fft |
||||
STACK_MAIN |
||||
8192 |
||||
COMPILE_FLAGS |
||||
${MAX_CUSTOM_OPT_LEVEL} |
||||
INCLUDES |
||||
${ROOT}/CMSIS/Core/Include |
||||
${DSP}/Include |
||||
SRCS |
||||
GyroFFT.cpp |
||||
GyroFFT.hpp |
||||
|
||||
${DSP}/Source/BasicMathFunctions/arm_shift_q15.c |
||||
|
||||
${DSP}/Source/CommonTables/arm_common_tables.c |
||||
${DSP}/Source/CommonTables/arm_const_structs.c |
||||
|
||||
${DSP}/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c |
||||
|
||||
${DSP}/Source/TransformFunctions/arm_bitreversal2.c |
||||
|
||||
#${DSP}/Source/TransformFunctions/arm_cfft_init_q15.c |
||||
${DSP}/Source/TransformFunctions/arm_cfft_q15.c |
||||
${DSP}/Source/TransformFunctions/arm_cfft_radix4_q15.c |
||||
|
||||
${DSP}/Source/TransformFunctions/arm_rfft_init_q15.c |
||||
${DSP}/Source/TransformFunctions/arm_rfft_q15.c |
||||
#${DSP}/Source/TransformFunctions/arm_rfft_radix4_q15.c |
||||
|
||||
${DSP}/Source/SupportFunctions/arm_float_to_q15.c |
||||
${DSP}/Source/BasicMathFunctions/arm_mult_q15.c |
||||
|
||||
DEPENDS |
||||
git_cmsis_v5 |
||||
px4_work_queue |
||||
) |
@ -0,0 +1,310 @@
@@ -0,0 +1,310 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "GyroFFT.hpp" |
||||
|
||||
#include <drivers/drv_hrt.h> |
||||
#include <mathlib/math/Limits.hpp> |
||||
#include <mathlib/math/Functions.hpp> |
||||
|
||||
using namespace matrix; |
||||
using namespace time_literals; |
||||
using math::radians; |
||||
|
||||
GyroFFT::GyroFFT() : |
||||
ModuleParams(nullptr), |
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) |
||||
{ |
||||
for (int axis = 0; axis < 3; axis++) { |
||||
arm_rfft_init_q15(&_rfft_q15[axis], FFT_LENGTH, 0, 1); |
||||
} |
||||
|
||||
// init Hanning window
|
||||
float hanning_window[FFT_LENGTH]; |
||||
|
||||
for (int n = 0; n < FFT_LENGTH; n++) { |
||||
hanning_window[n] = 0.5f - 0.5f * cosf(2.f * M_PI_F * n / (FFT_LENGTH - 1)); |
||||
} |
||||
|
||||
arm_float_to_q15(hanning_window, _hanning_window, FFT_LENGTH); |
||||
} |
||||
|
||||
GyroFFT::~GyroFFT() |
||||
{ |
||||
perf_free(_cycle_perf); |
||||
perf_free(_cycle_interval_perf); |
||||
perf_free(_fft_perf); |
||||
perf_free(_gyro_fifo_generation_gap_perf); |
||||
} |
||||
|
||||
bool GyroFFT::init() |
||||
{ |
||||
if (!SensorSelectionUpdate(true)) { |
||||
PX4_ERR("sensor_gyro_fifo callback registration failed!"); |
||||
return false; |
||||
} |
||||
|
||||
return true; |
||||
} |
||||
|
||||
bool GyroFFT::SensorSelectionUpdate(bool force) |
||||
{ |
||||
if (_sensor_selection_sub.updated() || force) { |
||||
sensor_selection_s sensor_selection{}; |
||||
_sensor_selection_sub.copy(&sensor_selection); |
||||
|
||||
if (_selected_sensor_device_id != sensor_selection.gyro_device_id) { |
||||
for (uint8_t i = 0; i < MAX_SENSOR_COUNT; i++) { |
||||
uORB::SubscriptionData<sensor_gyro_fifo_s> sensor_gyro_fifo_sub{ORB_ID(sensor_gyro_fifo), i}; |
||||
|
||||
if ((sensor_gyro_fifo_sub.get().device_id != 0) |
||||
&& (sensor_gyro_fifo_sub.get().device_id == sensor_selection.gyro_device_id)) { |
||||
|
||||
if (_sensor_gyro_fifo_sub.ChangeInstance(i) && _sensor_gyro_fifo_sub.registerCallback()) { |
||||
return true; |
||||
} |
||||
} |
||||
} |
||||
|
||||
PX4_ERR("unable to find or subscribe to selected sensor (%d)", sensor_selection.gyro_device_id); |
||||
} |
||||
} |
||||
|
||||
return false; |
||||
} |
||||
|
||||
// helper function used for frequency estimation
|
||||
static constexpr float tau(float x) |
||||
{ |
||||
float p1 = logf(3.f * powf(x, 2.f) + 6 * x + 1); |
||||
float part1 = x + 1 - sqrtf(2.f / 3.f); |
||||
float part2 = x + 1 + sqrtf(2.f / 3.f); |
||||
float p2 = logf(part1 / part2); |
||||
return (1.f / 4.f * p1 - sqrtf(6) / 24 * p2); |
||||
} |
||||
|
||||
void GyroFFT::Run() |
||||
{ |
||||
if (should_exit()) { |
||||
_sensor_gyro_fifo_sub.unregisterCallback(); |
||||
exit_and_cleanup(); |
||||
return; |
||||
} |
||||
|
||||
// backup schedule
|
||||
ScheduleDelayed(500_ms); |
||||
|
||||
perf_begin(_cycle_perf); |
||||
perf_count(_cycle_interval_perf); |
||||
|
||||
// Check if parameters have changed
|
||||
if (_parameter_update_sub.updated()) { |
||||
// clear update
|
||||
parameter_update_s param_update; |
||||
_parameter_update_sub.copy(¶m_update); |
||||
|
||||
updateParams(); |
||||
} |
||||
|
||||
SensorSelectionUpdate(); |
||||
|
||||
// run on sensor gyro fifo updates
|
||||
sensor_gyro_fifo_s sensor_gyro_fifo; |
||||
|
||||
while (_sensor_gyro_fifo_sub.update(&sensor_gyro_fifo)) { |
||||
|
||||
if (_sensor_gyro_fifo_sub.get_last_generation() != _gyro_last_generation + 1) { |
||||
// force reset if we've missed a sample
|
||||
_fft_buffer_index[0] = 0; |
||||
_fft_buffer_index[1] = 0; |
||||
_fft_buffer_index[2] = 0; |
||||
|
||||
perf_count(_gyro_fifo_generation_gap_perf); |
||||
} |
||||
|
||||
_gyro_last_generation = _sensor_gyro_fifo_sub.get_last_generation(); |
||||
|
||||
const int N = sensor_gyro_fifo.samples; |
||||
|
||||
for (int axis = 0; axis < 3; axis++) { |
||||
int16_t *input = nullptr; |
||||
|
||||
switch (axis) { |
||||
case 0: |
||||
input = sensor_gyro_fifo.x; |
||||
break; |
||||
|
||||
case 1: |
||||
input = sensor_gyro_fifo.y; |
||||
break; |
||||
|
||||
case 2: |
||||
input = sensor_gyro_fifo.z; |
||||
break; |
||||
} |
||||
|
||||
for (int n = 0; n < N; n++) { |
||||
int &buffer_index = _fft_buffer_index[axis]; |
||||
|
||||
_data_buffer[axis][buffer_index] = input[n] / 2; |
||||
|
||||
buffer_index++; |
||||
|
||||
// if we have enough samples, begin processing
|
||||
if (buffer_index >= FFT_LENGTH) { |
||||
|
||||
arm_mult_q15(_data_buffer[axis], _hanning_window, _fft_input_buffer, FFT_LENGTH); |
||||
|
||||
perf_begin(_fft_perf); |
||||
arm_rfft_q15(&_rfft_q15[axis], _fft_input_buffer, _fft_outupt_buffer); |
||||
perf_end(_fft_perf); |
||||
|
||||
|
||||
// find peak location using Quinn's Second Estimator (2020-06-14: http://dspguru.com/dsp/howtos/how-to-interpolate-fft-peak/)
|
||||
int16_t max_peak = 0; |
||||
uint16_t max_peak_index = 0; |
||||
|
||||
// start at 1 to skip DC
|
||||
for (uint16_t bucket_index = 1; bucket_index < FFT_LENGTH; bucket_index++) { |
||||
if (abs(_fft_outupt_buffer[bucket_index]) >= max_peak) { |
||||
max_peak_index = bucket_index; |
||||
max_peak = abs(_fft_outupt_buffer[bucket_index]); |
||||
} |
||||
} |
||||
|
||||
|
||||
int k = max_peak_index; |
||||
float divider = powf(_fft_outupt_buffer[k], 2.f); |
||||
float ap = (_fft_outupt_buffer[k + 1] * _fft_outupt_buffer[k]) / divider; |
||||
float dp = -ap / (1.f - ap); |
||||
float am = (_fft_outupt_buffer[k - 1] * _fft_outupt_buffer[k]) / divider; |
||||
|
||||
float dm = am / (1.f - am); |
||||
float d = (dp + dm) / 2 + tau(dp * dp) - tau(dm * dm); |
||||
|
||||
float adjustedBinLocation = k + d; |
||||
float peakFreqAdjusted = (_gyro_sample_rate * adjustedBinLocation / (FFT_LENGTH * 2)); |
||||
|
||||
|
||||
// publish sensor_gyro_fft_axis (one instance per axis)
|
||||
sensor_gyro_fft_axis_s sensor_gyro_fft_axis{}; |
||||
const int N_publish = math::min((unsigned)FFT_LENGTH, |
||||
sizeof(sensor_gyro_fft_axis_s::fft) / sizeof(sensor_gyro_fft_axis_s::fft[0])); |
||||
memcpy(sensor_gyro_fft_axis.fft, _fft_outupt_buffer, N_publish); |
||||
|
||||
sensor_gyro_fft_axis.resolution_hz = _gyro_sample_rate / (FFT_LENGTH * 2); |
||||
|
||||
sensor_gyro_fft_axis.peak_index = max_peak_index; |
||||
sensor_gyro_fft_axis.peak_frequency = max_peak_index * sensor_gyro_fft_axis.resolution_hz; |
||||
|
||||
sensor_gyro_fft_axis.peak_index_quinns = adjustedBinLocation; |
||||
sensor_gyro_fft_axis.peak_frequency_quinns = peakFreqAdjusted; |
||||
|
||||
sensor_gyro_fft_axis.samples = FFT_LENGTH; |
||||
sensor_gyro_fft_axis.dt = 1e6f / _gyro_sample_rate; |
||||
sensor_gyro_fft_axis.device_id = sensor_gyro_fifo.device_id; |
||||
sensor_gyro_fft_axis.axis = axis; |
||||
sensor_gyro_fft_axis.timestamp_sample = sensor_gyro_fifo.timestamp_sample; |
||||
sensor_gyro_fft_axis.timestamp = hrt_absolute_time(); |
||||
_sensor_gyro_fft_axis_pub[axis].publish(sensor_gyro_fft_axis); |
||||
|
||||
// reset
|
||||
buffer_index = 0; |
||||
} |
||||
} |
||||
} |
||||
} |
||||
|
||||
perf_end(_cycle_perf); |
||||
} |
||||
|
||||
int GyroFFT::task_spawn(int argc, char *argv[]) |
||||
{ |
||||
GyroFFT *instance = new GyroFFT(); |
||||
|
||||
if (instance) { |
||||
_object.store(instance); |
||||
_task_id = task_id_is_work_queue; |
||||
|
||||
if (instance->init()) { |
||||
return PX4_OK; |
||||
} |
||||
|
||||
} else { |
||||
PX4_ERR("alloc failed"); |
||||
} |
||||
|
||||
delete instance; |
||||
_object.store(nullptr); |
||||
_task_id = -1; |
||||
|
||||
return PX4_ERROR; |
||||
} |
||||
|
||||
int GyroFFT::print_status() |
||||
{ |
||||
perf_print_counter(_cycle_perf); |
||||
perf_print_counter(_cycle_interval_perf); |
||||
perf_print_counter(_fft_perf); |
||||
perf_print_counter(_gyro_fifo_generation_gap_perf); |
||||
return 0; |
||||
} |
||||
|
||||
int GyroFFT::custom_command(int argc, char *argv[]) |
||||
{ |
||||
return print_usage("unknown command"); |
||||
} |
||||
|
||||
int GyroFFT::print_usage(const char *reason) |
||||
{ |
||||
if (reason) { |
||||
PX4_WARN("%s\n", reason); |
||||
} |
||||
|
||||
PRINT_MODULE_DESCRIPTION( |
||||
R"DESCR_STR( |
||||
### Description |
||||
|
||||
)DESCR_STR"); |
||||
|
||||
PRINT_MODULE_USAGE_NAME("gyro_fft", "system"); |
||||
PRINT_MODULE_USAGE_COMMAND("start"); |
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); |
||||
|
||||
return 0; |
||||
} |
||||
|
||||
extern "C" __EXPORT int gyro_fft_main(int argc, char *argv[]) |
||||
{ |
||||
return GyroFFT::main(argc, argv); |
||||
} |
@ -0,0 +1,114 @@
@@ -0,0 +1,114 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <lib/matrix/matrix/math.hpp> |
||||
#include <lib/perf/perf_counter.h> |
||||
#include <px4_platform_common/defines.h> |
||||
#include <px4_platform_common/module.h> |
||||
#include <px4_platform_common/module_params.h> |
||||
#include <px4_platform_common/posix.h> |
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> |
||||
#include <uORB/Publication.hpp> |
||||
#include <uORB/PublicationMulti.hpp> |
||||
#include <uORB/Subscription.hpp> |
||||
#include <uORB/SubscriptionCallback.hpp> |
||||
#include <uORB/topics/parameter_update.h> |
||||
#include <uORB/topics/sensor_gyro_fft.h> |
||||
#include <uORB/topics/sensor_gyro_fft_axis.h> |
||||
#include <uORB/topics/sensor_gyro_fifo.h> |
||||
#include <uORB/topics/sensor_selection.h> |
||||
|
||||
#include "arm_math.h" |
||||
#include "arm_const_structs.h" |
||||
|
||||
class GyroFFT : public ModuleBase<GyroFFT>, public ModuleParams, public px4::ScheduledWorkItem |
||||
{ |
||||
public: |
||||
GyroFFT(); |
||||
~GyroFFT() override; |
||||
|
||||
/** @see ModuleBase */ |
||||
static int task_spawn(int argc, char *argv[]); |
||||
|
||||
/** @see ModuleBase */ |
||||
static int custom_command(int argc, char *argv[]); |
||||
|
||||
/** @see ModuleBase */ |
||||
static int print_usage(const char *reason = nullptr); |
||||
|
||||
/** @see ModuleBase::print_status() */ |
||||
int print_status() override; |
||||
|
||||
bool init(); |
||||
|
||||
private: |
||||
void Run() override; |
||||
bool SensorSelectionUpdate(bool force = false); |
||||
|
||||
static constexpr int MAX_SENSOR_COUNT = 3; |
||||
|
||||
uORB::Publication<sensor_gyro_fft_s> _sensor_gyro_fft_pub{ORB_ID(sensor_gyro_fft)}; |
||||
uORB::Publication<sensor_gyro_fft_axis_s> _sensor_gyro_fft_axis_pub[3] { |
||||
ORB_ID(sensor_gyro_fft_axis), |
||||
ORB_ID(sensor_gyro_fft_axis), |
||||
ORB_ID(sensor_gyro_fft_axis), |
||||
}; |
||||
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; |
||||
uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; |
||||
|
||||
uORB::SubscriptionCallbackWorkItem _sensor_gyro_fifo_sub{this, ORB_ID(sensor_gyro_fifo)}; |
||||
|
||||
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; |
||||
perf_counter_t _cycle_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")}; |
||||
perf_counter_t _fft_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": FFT")}; |
||||
perf_counter_t _gyro_fifo_generation_gap_perf{perf_alloc(PC_COUNT, MODULE_NAME": gyro FIFO data gap")}; |
||||
|
||||
uint32_t _selected_sensor_device_id{0}; |
||||
|
||||
static constexpr uint16_t FFT_LENGTH = 1024; |
||||
arm_rfft_instance_q15 _rfft_q15[3]; |
||||
|
||||
q15_t _data_buffer[3][FFT_LENGTH] {}; |
||||
q15_t _hanning_window[FFT_LENGTH] {}; |
||||
q15_t _fft_input_buffer[FFT_LENGTH] {}; |
||||
q15_t _fft_outupt_buffer[FFT_LENGTH * 2] {}; |
||||
|
||||
float _gyro_sample_rate{8000}; // 8 kHz default
|
||||
|
||||
int _fft_buffer_index[3] {}; |
||||
|
||||
unsigned _gyro_last_generation{0}; |
||||
}; |
Loading…
Reference in new issue