Skip to content

Commit

Permalink
Merge branch 'master' into release_2.5.1
Browse files Browse the repository at this point in the history
  • Loading branch information
digitalentity authored Jun 16, 2020
2 parents 098a574 + 706da4a commit 8034b35
Show file tree
Hide file tree
Showing 33 changed files with 415 additions and 221 deletions.
2 changes: 2 additions & 0 deletions docs/Board - OMNIBUS.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# Board - OMNIBUS F3

> This board is not supported in recent INAV releases
## Hardware Features

Refer to the product web page:
Expand Down
5 changes: 4 additions & 1 deletion docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -399,12 +399,15 @@ A shorter form is also supported to enable and disable functions using `serial <
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH |
| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH |
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL |
| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL |
| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL |
| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW |
| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW |
| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW |
| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW |
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff |
| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point |
Expand Down Expand Up @@ -506,7 +509,6 @@ A shorter form is also supported to enable and disable functions using `serial <
| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. |
| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. |
| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used |
| use_dterm_fir_filter | ON | Setting to **OFF** disabled extra filter on Dterm. **OFF** offers faster Dterm and better inflight performance with a cost of being more sensitive to gyro noise. Small and relatively clean multirotors (7 inches and below) are suggested to use **OFF** setting. If motors are getting too hot, switch back to **ON** |
| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. |
| sim_pin | Empty string | PIN code for the SIM module |
| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 |
Expand All @@ -522,3 +524,4 @@ A shorter form is also supported to enable and disable functions using `serial <
| antigravity_accelerator | 1 | |
| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain |
| sim_pin | | PIN for GSM card module |
| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky |
24 changes: 17 additions & 7 deletions docs/development/Development.md
Original file line number Diff line number Diff line change
Expand Up @@ -77,24 +77,34 @@ The main flow for a contributing is as follows:
1. Login to github, go to the INAV repository and press `fork`.
2. Then using the command line/terminal on your computer: `git clone <url to YOUR fork>`
3. `cd inav`
4. `git checkout development`
4. `git checkout master`
5. `git checkout -b my-new-code`
6. Make changes
7. `git add <files that have changed>`
8. `git commit`
9. `git push origin my-new-code`
10. Create pull request using github UI to merge your changes from your new branch into `inav/development`
10. Create pull request using github UI to merge your changes from your new branch into `inav/master`
11. Repeat from step 4 for new other changes.

The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `development` branch.
The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `master` branch.

Later, you can get the changes from the INAV repo into your `development` branch by adding INAV as a git remote and merging from it as follows:
Later, you can get the changes from the INAV repo into your `master` branch by adding INAV as a git remote and merging from it as follows:

1. `git remote add upstream https://github.com/iNavFlight/inav.git`
2. `git checkout development`
2. `git checkout master`
3. `git fetch upstream`
4. `git merge upstream/development`
5. `git push origin development` is an optional step that will update your fork on github
4. `git merge upstream/master`
5. `git push origin master` is an optional step that will update your fork on github


You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual.

## Branching and release workflow

Normally, all development occurs on the `master` branch. Every release will have it's own branch named `release_x.y.z`.

During release candidate cycle we will follow the process outlined below:

1. Create a release branch `release_x.y.z`
2. All bug fixes found in the release candidates will be merged into `release_x.y.z` branch and not into the `master`.
3. After final release is made, the branch `release_x.y.z` is locked, and merged into `master` bringing all of the bug fixes into the development branch. Merge conflicts that may arise at this stage are resolved manually.
2 changes: 1 addition & 1 deletion make/release.mk
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV

RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL

RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2
RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
Expand Down
1 change: 1 addition & 0 deletions make/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ COMMON_SRC = \
flight/gyroanalyse.c \
flight/rpm_filter.c \
flight/dynamic_gyro_notch.c \
flight/kalman.c \
io/beeper.c \
io/esc_serialshot.c \
io/servo_sbus.c \
Expand Down
2 changes: 1 addition & 1 deletion make/targets.mk
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ endif

GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD
GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX
GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX
GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
Expand Down
11 changes: 4 additions & 7 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1717,8 +1717,6 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_hz", "%d", pidProfile()->dterm_lpf2_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_type", "%d", pidProfile()->dterm_lpf2_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", pidProfile()->dterm_soft_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband);
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
Expand All @@ -1728,10 +1726,10 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
gyroConfig()->gyro_soft_notch_hz_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
gyroConfig()->gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_notch_hz,
0);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_notch_cutoff,
1);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", accelerometerConfig()->acc_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
Expand All @@ -1747,7 +1745,6 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("gyro_stage2_lowpass_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%f", (double)pidProfile()->dterm_setpoint_weight);
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw);
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw);
Expand Down
2 changes: 2 additions & 0 deletions src/main/build/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,5 +71,7 @@ typedef enum {
DEBUG_DYNAMIC_FILTER,
DEBUG_DYNAMIC_FILTER_FREQUENCY,
DEBUG_IRLOCK,
DEBUG_CD,
DEBUG_KALMAN,
DEBUG_COUNT
} debugType_e;
4 changes: 2 additions & 2 deletions src/main/build/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
*/

#define FC_VERSION_MAJOR 2 // 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_PATCH_LEVEL 1 // increment when a bug is fixed
#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 STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
Expand Down
38 changes: 1 addition & 37 deletions src/main/common/filter.c
Original file line number Diff line number Diff line change
Expand Up @@ -231,40 +231,4 @@ FAST_CODE void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint
filter->x2 = x2;
filter->y1 = y1;
filter->y2 = y2;
}

/*
* FIR filter
*/
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength)
{
filter->buf = buf;
filter->bufLength = bufLength;
filter->coeffs = coeffs;
filter->coeffsLength = coeffsLength;
memset(filter->buf, 0, sizeof(float) * filter->bufLength);
}

/*
* FIR filter initialisation
* If FIR filter is just used for averaging, coeffs can be set to NULL
*/
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs)
{
firFilterInit2(filter, buf, bufLength, coeffs, bufLength);
}

void firFilterUpdate(firFilter_t *filter, float input)
{
memmove(&filter->buf[1], &filter->buf[0], (filter->bufLength-1) * sizeof(float));
filter->buf[0] = input;
}

float firFilterApply(const firFilter_t *filter)
{
float ret = 0.0f;
for (int ii = 0; ii < filter->coeffsLength; ++ii) {
ret += filter->coeffs[ii] * filter->buf[ii];
}
return ret;
}
}
5 changes: 0 additions & 5 deletions src/main/common/filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,3 @@ float biquadFilterReset(biquadFilter_t *filter, float value);
float biquadFilterApplyDF1(biquadFilter_t *filter, float input);
float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz);
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);

void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength);
void firFilterUpdate(firFilter_t *filter, float input);
float firFilterApply(const firFilter_t *filter);
8 changes: 8 additions & 0 deletions src/main/drivers/serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -111,3 +111,11 @@ bool serialIsConnected(const serialPort_t *instance)
// If API is not defined - assume connected
return true;
}

bool serialIsIdle(serialPort_t *instance)
{
if (instance->vTable->isIdle)
return instance->vTable->isIdle(instance);
else
return false;
}
3 changes: 3 additions & 0 deletions src/main/drivers/serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ struct serialPortVTable {

bool (*isConnected)(const serialPort_t *instance);

bool (*isIdle)(serialPort_t *instance);

// Optional functions used to buffer large writes.
void (*beginWrite)(serialPort_t *instance);
void (*endWrite)(serialPort_t *instance);
Expand All @@ -111,6 +113,7 @@ bool isSerialTransmitBufferEmpty(const serialPort_t *instance);
void serialPrint(serialPort_t *instance, const char *str);
uint32_t serialGetBaudRate(serialPort_t *instance);
bool serialIsConnected(const serialPort_t *instance);
bool serialIsIdle(serialPort_t *instance);

// A shim that adapts the bufWriter API to the serialWriteBuf() API.
void serialWriteBufShim(void *instance, const uint8_t *data, int count);
Expand Down
3 changes: 2 additions & 1 deletion src/main/drivers/serial_softserial.c
Original file line number Diff line number Diff line change
Expand Up @@ -628,7 +628,8 @@ static const struct serialPortVTable softSerialVTable = {
.isConnected = NULL,
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL
.endWrite = NULL,
.isIdle = NULL,
};

#endif
12 changes: 12 additions & 0 deletions src/main/drivers/serial_uart.c
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
}

bool isUartIdle(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t *)instance;
if(USART_GetFlagStatus(s->USARTx, USART_FLAG_IDLE)) {
uartClearIdleFlag(s);
return true;
} else {
return false;
}
}

const struct serialPortVTable uartVTable[] = {
{
.serialWrite = uartWrite,
Expand All @@ -260,5 +271,6 @@ const struct serialPortVTable uartVTable[] = {
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,
.isIdle = isUartIdle,
}
};
1 change: 1 addition & 0 deletions src/main/drivers/serial_uart.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ typedef struct {
} uartPort_t;

void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins);
void uartClearIdleFlag(uartPort_t *s);
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options);

// serialPort API
Expand Down
12 changes: 12 additions & 0 deletions src/main/drivers/serial_uart_hal.c
Original file line number Diff line number Diff line change
Expand Up @@ -246,6 +246,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
__HAL_UART_ENABLE_IT(&s->Handle, UART_IT_TXE);
}

bool isUartIdle(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t *)instance;
if(__HAL_UART_GET_FLAG(&s->Handle, UART_FLAG_IDLE)) {
__HAL_UART_CLEAR_IDLEFLAG(&s->Handle);
return true;
} else {
return false;
}
}

const struct serialPortVTable uartVTable[] = {
{
.serialWrite = uartWrite,
Expand All @@ -259,5 +270,6 @@ const struct serialPortVTable uartVTable[] = {
.writeBuf = NULL,
.beginWrite = NULL,
.endWrite = NULL,
.isIdle = isUartIdle,
}
};
5 changes: 5 additions & 0 deletions src/main/drivers/serial_uart_stm32f30x.c
Original file line number Diff line number Diff line change
Expand Up @@ -351,6 +351,11 @@ void usartIrqHandler(uartPort_t *s)
}
}

void uartClearIdleFlag(uartPort_t *s)
{
USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE);
}

#ifdef USE_UART1
void USART1_IRQHandler(void)
{
Expand Down
6 changes: 6 additions & 0 deletions src/main/drivers/serial_uart_stm32f4xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -253,6 +253,12 @@ void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
}
}

void uartClearIdleFlag(uartPort_t *s)
{
(void) s->USARTx->SR;
(void) s->USARTx->DR;
}

uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
uartPort_t *s;
Expand Down
3 changes: 2 additions & 1 deletion src/main/drivers/serial_usb_vcp.c
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,8 @@ static const struct serialPortVTable usbVTable[] = {
.isConnected = usbVcpIsConnected,
.writeBuf = usbVcpWriteBuf,
.beginWrite = usbVcpBeginWrite,
.endWrite = usbVcpEndWrite
.endWrite = usbVcpEndWrite,
.isIdle = NULL,
}
};

Expand Down
10 changes: 2 additions & 8 deletions src/main/fc/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -167,14 +167,8 @@ uint32_t getLooptime(void) {

void validateAndFixConfig(void)
{
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
}
if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
}
if (pidProfile()->dterm_soft_notch_cutoff >= pidProfile()->dterm_soft_notch_hz) {
pidProfileMutable()->dterm_soft_notch_hz = 0;
if (gyroConfig()->gyro_notch_cutoff >= gyroConfig()->gyro_notch_hz) {
gyroConfigMutable()->gyro_notch_hz = 0;
}
if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) {
accelerometerConfigMutable()->acc_notch_hz = 0;
Expand Down
Loading

0 comments on commit 8034b35

Please sign in to comment.