Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding headtracker_max_angle and headtracker_yaw_reset_shimmy #4

Closed
wants to merge 22 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
565de1b
Use the cached value of useDshotTelemetry to ensure consistent runtim…
SteveCEvans Apr 27, 2024
c155f58
Update EEPROM version for 4.5 (#13498)
haslinghuis Apr 28, 2024
59c93ba
Update version to 4.6 (#13499)
haslinghuis Apr 28, 2024
a000913
Fix stm32h730 hardcoded target IO (#13604)
hydra Apr 29, 2024
4640a5d
cppcheck - minor problems fixed (#13609)
ledvinap Apr 30, 2024
62aebac
Update README.md (#13615)
TheIsotopes May 4, 2024
5fd3852
battery - fix BATTERY_NOT_PRESENT detection, detection logic change (…
ledvinap May 4, 2024
d1ffa46
New led functions gps bar battery bar altitude (#13404)
jonas-becker May 5, 2024
d5af7d2
Add CRSF vario sensor support (#13558)
haslinghuis May 9, 2024
5a28ce5
Make Cppcheck happier revived (#13566)
haslinghuis May 10, 2024
33ead2d
Fix ICM20469 (#13616)
haslinghuis May 10, 2024
d778a4f
timers - remove obsolete defines from SITL and unittests (#13597)
ledvinap May 10, 2024
764d82d
Remove canvas configuration in cli (#13595)
haslinghuis May 10, 2024
7ae92a9
minor define fixes found during documentation work (#13631)
ctzsnooze May 11, 2024
076049e
Update CRSF spec (#13614)
haslinghuis May 11, 2024
e55918c
Display one of four logos on arming (#13057)
SteveCEvans May 11, 2024
2d3c8ee
Remove superfluous checks of useDshotTelemetry (#13633)
SteveCEvans May 12, 2024
dc173be
Headtracker output on SBus
SteveCEvans May 21, 2024
1890351
Add headshimmy reset
SteveCEvans May 24, 2024
bd04508
Remove debug
SteveCEvans May 24, 2024
6cba879
headtracker_max_angle
May 24, 2024
0aa1135
headtracker_yaw_reset_shimmy
May 24, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@ This fork differs from Baseflight and Cleanflight in that it focuses on flight p

| Date | Event |
| - | - |
| 01-11-2022 | Firmware 4.4 Feature freeze |
| 29-01-2023 | Firmware 4.4 Release |
| 28-04-2024 | Firmware 4.5 Release |


## News
Expand Down
2 changes: 0 additions & 2 deletions lib/main/MAVLink/mavlink_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,7 +289,6 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa

mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0;

status->msg_received = 0;

Expand Down Expand Up @@ -425,7 +424,6 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break;
}

bufferIndex++;
// If a message has been sucessfully decoded, check index
if (status->msg_received == 1)
{
Expand Down
1 change: 1 addition & 0 deletions mk/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,7 @@ COMMON_SRC = \
io/rcdevice_cam.c \
io/rcdevice.c \
io/gps.c \
io/headtracker.c \
io/ledstrip.c \
io/pidaudio.c \
osd/osd.c \
Expand Down
4 changes: 2 additions & 2 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -469,7 +469,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case CONDITION(MOTOR_6_HAS_RPM):
case CONDITION(MOTOR_7_HAS_RPM):
case CONDITION(MOTOR_8_HAS_RPM):
return (getMotorCount() >= condition - CONDITION(MOTOR_1_HAS_RPM) + 1) && (motorConfig()->dev.useDshotTelemetry) && isFieldEnabled(FIELD_SELECT(RPM));
return (getMotorCount() >= condition - CONDITION(MOTOR_1_HAS_RPM) + 1) && useDshotTelemetry && isFieldEnabled(FIELD_SELECT(RPM));
#endif

case CONDITION(TRICOPTER):
Expand Down Expand Up @@ -1524,7 +1524,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_NOTCH_MIN_HZ, "%d", dynNotchConfig()->dyn_notch_min_hz);
#endif
#ifdef USE_DSHOT_TELEMETRY
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DSHOT_BIDIR, "%d", motorConfig()->dev.useDshotTelemetry);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DSHOT_BIDIR, "%d", useDshotTelemetry);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_POLES, "%d", motorConfig()->motorPoleCount);
#endif
#ifdef USE_RPM_FILTER
Expand Down
2 changes: 1 addition & 1 deletion src/main/build/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#define FC_FIRMWARE_NAME "Betaflight"
#define FC_FIRMWARE_IDENTIFIER "BTFL"
#define FC_VERSION_MAJOR 4 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed

#define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL)
Expand Down
35 changes: 18 additions & 17 deletions src/main/cli/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -453,6 +453,7 @@ static void cliPrintError(const char *cmdName, const char *format, ...)
va_list va;
va_start(va, format);
cliPrintErrorVa(cmdName, format, va);
va_end(va);

if (!cliWriter) {
// Supply our own linefeed in case we are printing inside a custom defaults operation
Expand All @@ -467,6 +468,7 @@ static void cliPrintErrorLinef(const char *cmdName, const char *format, ...)
va_list va;
va_start(va, format);
cliPrintErrorVa(cmdName, format, va);
va_end(va);
cliPrintInternal(cliErrorWriter, "\r\n");
}

Expand Down Expand Up @@ -1634,28 +1636,26 @@ static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *
static void cliAdjustmentRange(const char *cmdName, char *cmdline)
{
const char *format = "adjrange %u 0 %u %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;

if (isEmpty(cmdline)) {
printAdjustmentRange(DUMP_MASTER, adjustmentRanges(0), NULL, NULL);
} else {
ptr = cmdline;
i = atoi(ptr++);
int i = atoi(ptr++);
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
adjustmentRange_t *ar = adjustmentRangesMutable(i);
uint8_t validArgumentCount = 0;

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
// Was: slot
// Keeping the parameter to retain backwards compatibility for the command format.
validArgumentCount++;
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxChannelIndex = val;
validArgumentCount++;
Expand All @@ -1666,15 +1666,15 @@ static void cliAdjustmentRange(const char *cmdName, char *cmdline)

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
ar->adjustmentConfig = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxSwitchChannelIndex = val;
validArgumentCount++;
Expand All @@ -1693,13 +1693,13 @@ static void cliAdjustmentRange(const char *cmdName, char *cmdline)

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
ar->adjustmentCenter = val;
validArgumentCount++;
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
ar->adjustmentScale = val;
validArgumentCount++;
}
Expand Down Expand Up @@ -2614,7 +2614,6 @@ static void printVtx(dumpFlags_t dumpMask, const vtxConfig_t *vtxConfig, const v
static void cliVtx(const char *cmdName, char *cmdline)
{
const char *format = "vtx %u %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;

if (isEmpty(cmdline)) {
Expand All @@ -2630,37 +2629,37 @@ static void cliVtx(const char *cmdName, char *cmdline)
const uint8_t maxPowerIndex = VTX_TABLE_MAX_POWER_LEVELS;
#endif
ptr = cmdline;
i = atoi(ptr++);
int i = atoi(ptr++);
if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
vtxChannelActivationCondition_t *cac = &vtxConfigMutable()->vtxChannelActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
cac->auxChannelIndex = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxBandIndex) {
cac->band = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxChannelIndex) {
cac->channel = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxPowerIndex) {
cac->power= val;
validArgumentCount++;
Expand Down Expand Up @@ -4375,7 +4374,7 @@ STATIC_UNIT_TESTED void cliGet(const char *cmdName, char *cmdline)
}
}

static uint8_t getWordLength(char *bufBegin, char *bufEnd)
static uint8_t getWordLength(const char *bufBegin, const char *bufEnd)
{
while (*(bufEnd - 1) == ' ') {
bufEnd--;
Expand Down Expand Up @@ -5135,6 +5134,9 @@ const cliResourceValue_t resourceTable[] = {
DEFA( OWNER_PULLUP, PG_PULLUP_CONFIG, pinPullUpDownConfig_t, ioTag, PIN_PULL_UP_DOWN_COUNT ),
DEFA( OWNER_PULLDOWN, PG_PULLDOWN_CONFIG, pinPullUpDownConfig_t, ioTag, PIN_PULL_UP_DOWN_COUNT ),
#endif
#ifdef USE_HEADTRACKER
DEFS( OWNER_HEADTRACKER, PG_RX_CONFIG, rxConfig_t, headtracker_ioTag),
#endif
};

#undef DEFS
Expand Down Expand Up @@ -5436,9 +5438,8 @@ static void printTimerDmaoptDetails(const ioTag_t ioTag, const timerHardware_t *

if (printDetails) {
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timer->tim, timer->channel, dmaopt);
dmaCode_t dmaCode = 0;
if (dmaChannelSpec) {
dmaCode = dmaChannelSpec->code;
dmaCode_t dmaCode = dmaChannelSpec->code;
printValue(dumpMask, false,
"# pin %c%02d: " DMASPEC_FORMAT_STRING,
IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag),
Expand Down
10 changes: 10 additions & 0 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -769,6 +769,13 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_SERIAL_RX_PROVIDER, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
{ "serialrx_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_inverted) },
#endif
#ifdef USE_SERIALTX
{ "serialtx_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, serialtx_inverted) },
#endif
#ifdef USE_HEADTRACKER
{ "headtracker_max_angle", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 180}, PG_RX_CONFIG, offsetof(rxConfig_t, headtracker_max_angle) },
{ "headtracker_yaw_reset_shimmy",VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, headtracker_yaw_reset_shimmy) },
#endif
#ifdef USE_SPEKTRUM_BIND
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
{ "spektrum_sat_bind_autoreset", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
Expand Down Expand Up @@ -1380,6 +1387,7 @@ const clivalue_t valueTable[] = {
{ "osd_ah_invert", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, ahInvert) },
{ "osd_logo_on_arming", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_LOGO_ON_ARMING }, PG_OSD_CONFIG, offsetof(osdConfig_t, logo_on_arming) },
{ "osd_logo_on_arming_duration",VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 5, 50 }, PG_OSD_CONFIG, offsetof(osdConfig_t, logo_on_arming_duration) },
{ "osd_arming_logo", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, DISPLAYPORT_SEVERITY_COUNT - 1 }, PG_OSD_CONFIG, offsetof(osdConfig_t, arming_logo) },
#ifdef USE_OSD_QUICK_MENU
{ "osd_use_quick_menu", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, osd_use_quick_menu) },
#endif // USE_OSD_QUICK_MENU
Expand Down Expand Up @@ -1522,8 +1530,10 @@ const clivalue_t valueTable[] = {
{ "osd_aux_channel", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_OSD_CONFIG, offsetof(osdConfig_t, aux_channel) },
{ "osd_aux_scale", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 1000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, aux_scale) },
{ "osd_aux_symbol", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 255 }, PG_OSD_CONFIG, offsetof(osdConfig_t, aux_symbol) },
#ifdef OSD_CANVAS_SIZE_DEBUG
{ "osd_canvas_width", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 63 }, PG_OSD_CONFIG, offsetof(osdConfig_t, canvas_cols) },
{ "osd_canvas_height", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 31 }, PG_OSD_CONFIG, offsetof(osdConfig_t, canvas_rows) },
#endif
#ifdef USE_CRAFTNAME_MSGS
{ "osd_craftname_msgs", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, osd_craftname_msgs) },
#endif //USE_CRAFTNAME_MSGS
Expand Down
2 changes: 1 addition & 1 deletion src/main/cms/cms.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ static displayPort_t *cmsDisplayPortSelectNext(void)
return cmsDisplayPorts[cmsCurrentDevice];
}

bool cmsDisplayPortSelect(displayPort_t *instance)
bool cmsDisplayPortSelect(const displayPort_t *instance)
{
for (unsigned i = 0; i < cmsDeviceCount; i++) {
if (cmsDisplayPortSelectNext() == instance) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/cms/cms.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ extern displayPort_t *pCurrentDisplay;
void cmsInit(void);
void cmsHandler(timeUs_t currentTimeUs);

bool cmsDisplayPortSelect(displayPort_t *instance);
bool cmsDisplayPortSelect(const displayPort_t *instance);
void cmsMenuOpen(void);
const void *cmsMenuChange(displayPort_t *pPort, const void *ptr);
const void *cmsMenuExit(displayPort_t *pPort, const void *ptr);
Expand Down
18 changes: 9 additions & 9 deletions src/main/common/maths.c
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix)
#define QMF_SORTF(a,b) { if ((a)>(b)) QMF_SWAPF((a),(b)); }
#define QMF_SWAPF(a,b) { float temp=(a);(a)=(b);(b)=temp; }

int32_t quickMedianFilter3(int32_t * v)
int32_t quickMedianFilter3(const int32_t * v)
{
int32_t p[3];
QMF_COPY(p, v, 3);
Expand All @@ -238,7 +238,7 @@ int32_t quickMedianFilter3(int32_t * v)
return p[1];
}

int32_t quickMedianFilter5(int32_t * v)
int32_t quickMedianFilter5(const int32_t * v)
{
int32_t p[5];
QMF_COPY(p, v, 5);
Expand All @@ -249,7 +249,7 @@ int32_t quickMedianFilter5(int32_t * v)
return p[2];
}

int32_t quickMedianFilter7(int32_t * v)
int32_t quickMedianFilter7(const int32_t * v)
{
int32_t p[7];
QMF_COPY(p, v, 7);
Expand All @@ -262,7 +262,7 @@ int32_t quickMedianFilter7(int32_t * v)
return p[3];
}

int32_t quickMedianFilter9(int32_t * v)
int32_t quickMedianFilter9(const int32_t * v)
{
int32_t p[9];
QMF_COPY(p, v, 9);
Expand All @@ -277,7 +277,7 @@ int32_t quickMedianFilter9(int32_t * v)
return p[4];
}

float quickMedianFilter3f(float * v)
float quickMedianFilter3f(const float * v)
{
float p[3];
QMF_COPY(p, v, 3);
Expand All @@ -286,7 +286,7 @@ float quickMedianFilter3f(float * v)
return p[1];
}

float quickMedianFilter5f(float * v)
float quickMedianFilter5f(const float * v)
{
float p[5];
QMF_COPY(p, v, 5);
Expand All @@ -297,7 +297,7 @@ float quickMedianFilter5f(float * v)
return p[2];
}

float quickMedianFilter7f(float * v)
float quickMedianFilter7f(const float * v)
{
float p[7];
QMF_COPY(p, v, 7);
Expand All @@ -310,7 +310,7 @@ float quickMedianFilter7f(float * v)
return p[3];
}

float quickMedianFilter9f(float * v)
float quickMedianFilter9f(const float * v)
{
float p[9];
QMF_COPY(p, v, 9);
Expand All @@ -325,7 +325,7 @@ float quickMedianFilter9f(float * v)
return p[4];
}

void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count)
void arraySubInt32(int32_t *dest, const int32_t *array1, const int32_t *array2, int count)
{
for (int i = 0; i < count; i++) {
dest[i] = array1[i] - array2[i];
Expand Down
18 changes: 9 additions & 9 deletions src/main/common/maths.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,15 +120,15 @@ float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float des
void buildRotationMatrix(fp_angles_t *delta, fp_rotationMatrix_t *rotation);
void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix);

int32_t quickMedianFilter3(int32_t * v);
int32_t quickMedianFilter5(int32_t * v);
int32_t quickMedianFilter7(int32_t * v);
int32_t quickMedianFilter9(int32_t * v);
int32_t quickMedianFilter3(const int32_t * v);
int32_t quickMedianFilter5(const int32_t * v);
int32_t quickMedianFilter7(const int32_t * v);
int32_t quickMedianFilter9(const int32_t * v);

float quickMedianFilter3f(float * v);
float quickMedianFilter5f(float * v);
float quickMedianFilter7f(float * v);
float quickMedianFilter9f(float * v);
float quickMedianFilter3f(const float * v);
float quickMedianFilter5f(const float * v);
float quickMedianFilter7f(const float * v);
float quickMedianFilter9f(const float * v);

#if defined(FAST_MATH) || defined(VERY_FAST_MATH)
float sin_approx(float x);
Expand All @@ -150,7 +150,7 @@ float pow_approx(float a, float b);
#define pow_approx(a, b) powf(b, a)
#endif

void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
void arraySubInt32(int32_t *dest, const int32_t *array1, const int32_t *array2, int count);

int16_t qPercent(fix12_t q);
int16_t qMultiply(fix12_t q, int16_t input);
Expand Down
3 changes: 1 addition & 2 deletions src/main/common/sdft.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,8 @@ void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numB
if (!isInitialized) {
rPowerN = powf(SDFT_R, SDFT_SAMPLE_SIZE);
const float c = 2.0f * M_PIf / (float)SDFT_SAMPLE_SIZE;
float phi = 0.0f;
for (int i = 0; i < SDFT_BIN_COUNT; i++) {
phi = c * i;
float phi = c * i;
twiddle[i] = SDFT_R * (cos_approx(phi) + _Complex_I * sin_approx(phi));
}
isInitialized = true;
Expand Down
Loading