diff --git a/src/main/drivers/compass/compass_hmc5883l.c b/src/main/drivers/compass/compass_hmc5883l.c
index a0366ee19..4c6dc3ad2 100644
--- a/src/main/drivers/compass/compass_hmc5883l.c
+++ b/src/main/drivers/compass/compass_hmc5883l.c
@@ -169,7 +169,7 @@ static bool hmc5883lRead(int16_t *magData)
{
uint8_t buf[6];
#ifdef USE_MAG_SPI_HMC5883
- bool ack = hmc5883SpiReadCommand(MAG_DATA_REGISTER, 6, buf);
+ bool ack = hmc5883SpiReadCommand(MAG_DATA_REGISTER, 6, buf);
#else
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
#endif
@@ -202,7 +202,7 @@ static bool hmc5883lInit(void)
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
// The new gain setting is effective from the second measurement and on.
#ifdef USE_MAG_SPI_HMC5883
- hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
+ hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
#endif
@@ -211,7 +211,7 @@ static bool hmc5883lInit(void)
for (i = 0; i < 10; i++) { // Collect 10 samples
#ifdef USE_MAG_SPI_HMC5883
- hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
+ hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
#endif
@@ -233,7 +233,7 @@ static bool hmc5883lInit(void)
// Apply the negative bias. (Same gain)
#ifdef USE_MAG_SPI_HMC5883
- hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
+ hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
#endif
diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c
index 7d0e495b4..29167328c 100644
--- a/src/main/drivers/pwm_output.c
+++ b/src/main/drivers/pwm_output.c
@@ -151,7 +151,7 @@ static uint8_t loadDmaBufferDshot(motorDmaOutput_t *const motor, uint16_t packet
for (int i = 0; i < 16; i++) {
motor->dmaBuffer[i] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
packet <<= 1;
- }
+ }
return DSHOT_DMA_BUFFER_SIZE;
}
@@ -328,7 +328,7 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
*/
motors[motorIndex].pulseScale = ((motorConfig->motorPwmProtocol == PWM_TYPE_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
-
+
pwmOutConfig(&motors[motorIndex], timerHardware, hz, period, idlePulse, motorConfig->motorPwmInversion);
bool timerAlreadyUsed = false;
diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c
index 4181fed7e..714359de5 100644
--- a/src/main/drivers/sdcard.c
+++ b/src/main/drivers/sdcard.c
@@ -553,7 +553,7 @@ void sdcard_init(bool useDMA)
#ifdef SDCARD_DMA_CHANNEL_TX
useDMAForTx = useDMA;
if (useDMAForTx) {
- dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0);
+ dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0);
}
#else
// DMA is not available
diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h
index 2c74488ee..5efe413f8 100644
--- a/src/main/drivers/serial_tcp.h
+++ b/src/main/drivers/serial_tcp.h
@@ -29,13 +29,13 @@ typedef struct {
uint8_t rxBuffer[RX_BUFFER_SIZE];
uint8_t txBuffer[TX_BUFFER_SIZE];
- dyad_Stream *serv;
- dyad_Stream *conn;
- pthread_mutex_t txLock;
- pthread_mutex_t rxLock;
- bool connected;
- uint16_t clientCount;
- uint8_t id;
+ dyad_Stream *serv;
+ dyad_Stream *conn;
+ pthread_mutex_t txLock;
+ pthread_mutex_t rxLock;
+ bool connected;
+ uint16_t clientCount;
+ uint8_t id;
} tcpPort_t;
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
diff --git a/src/main/drivers/transponder_ir_arcitimer.c b/src/main/drivers/transponder_ir_arcitimer.c
index 2ec8214df..e8b9a7e22 100644
--- a/src/main/drivers/transponder_ir_arcitimer.c
+++ b/src/main/drivers/transponder_ir_arcitimer.c
@@ -60,7 +60,7 @@ void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8
const struct transponderVTable arcitimerTansponderVTable = {
- updateTransponderDMABufferArcitimer,
+ updateTransponderDMABufferArcitimer,
};
#endif
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index a405e8dac..9c23036c5 100644
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -234,7 +234,7 @@ void tryArm(void)
pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
}
}
- }
+ }
#endif
ENABLE_ARMING_FLAG(ARMED);
diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c
index f4e472d4f..d00e0c078 100644
--- a/src/main/flight/imu.c
+++ b/src/main/flight/imu.c
@@ -427,16 +427,16 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
#endif
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC)
- UNUSED(imuMahonyAHRSupdate);
- UNUSED(useAcc);
- UNUSED(useMag);
- UNUSED(useYaw);
- UNUSED(rawYawError);
+ UNUSED(imuMahonyAHRSupdate);
+ UNUSED(useAcc);
+ UNUSED(useMag);
+ UNUSED(useYaw);
+ UNUSED(rawYawError);
#else
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
-// printf("[imu]deltaT = %u, imuDeltaT = %u, currentTimeUs = %u, micros64_real = %lu\n", deltaT, imuDeltaT, currentTimeUs, micros64_real());
- deltaT = imuDeltaT;
+// printf("[imu]deltaT = %u, imuDeltaT = %u, currentTimeUs = %u, micros64_real = %lu\n", deltaT, imuDeltaT, currentTimeUs, micros64_real());
+ deltaT = imuDeltaT;
#endif
imuMahonyAHRSupdate(deltaT * 1e-6f,
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index bba155a49..b26cb4aa0 100755
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -561,8 +561,8 @@ void mixTable(pidProfile_t *pidProfile)
float motorMixMax = 0, motorMixMin = 0;
const int yawDirection = GET_DIRECTION(mixerConfig()->yaw_motors_reversed);
int motorDirection = GET_DIRECTION(isMotorsReversed());
-
-
+
+
for (int i = 0; i < motorCount; i++) {
float mix =
scaledAxisPidRoll * currentMixer[i].roll * (motorDirection) +
diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c
index 8c9da5069..69e4332f6 100644
--- a/src/main/io/ledstrip.c
+++ b/src/main/io/ledstrip.c
@@ -446,52 +446,52 @@ static void applyLedFixedLayers()
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];
hsvColor_t color = *getSC(LED_SCOLOR_BACKGROUND);
- hsvColor_t nextColor = *getSC(LED_SCOLOR_BACKGROUND); //next color above the one selected, or color 0 if your are at the maximum
- hsvColor_t previousColor = *getSC(LED_SCOLOR_BACKGROUND); //Previous color to the one selected, modulo color count
+ hsvColor_t nextColor = *getSC(LED_SCOLOR_BACKGROUND); //next color above the one selected, or color 0 if your are at the maximum
+ hsvColor_t previousColor = *getSC(LED_SCOLOR_BACKGROUND); //Previous color to the one selected, modulo color count
int fn = ledGetFunction(ledConfig);
int hOffset = HSV_HUE_MAX;
switch (fn) {
- case LED_FUNCTION_COLOR:
- color = ledStripConfig()->colors[ledGetColor(ledConfig)];
- nextColor = ledStripConfig()->colors[(ledGetColor(ledConfig) + 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
- previousColor = ledStripConfig()->colors[(ledGetColor(ledConfig) - 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
- break;
+ case LED_FUNCTION_COLOR:
+ color = ledStripConfig()->colors[ledGetColor(ledConfig)];
+ nextColor = ledStripConfig()->colors[(ledGetColor(ledConfig) + 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
+ previousColor = ledStripConfig()->colors[(ledGetColor(ledConfig) - 1 + LED_CONFIGURABLE_COLOR_COUNT) % LED_CONFIGURABLE_COLOR_COUNT];
+ break;
- case LED_FUNCTION_FLIGHT_MODE:
- for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++)
- if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) {
- const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]);
- if (directionalColor) {
- color = *directionalColor;
- }
-
- break; // stop on first match
+ case LED_FUNCTION_FLIGHT_MODE:
+ for (unsigned i = 0; i < ARRAYLEN(flightModeToLed); i++)
+ if (!flightModeToLed[i].flightMode || FLIGHT_MODE(flightModeToLed[i].flightMode)) {
+ const hsvColor_t *directionalColor = getDirectionalModeColor(ledIndex, &ledStripConfig()->modeColors[flightModeToLed[i].ledMode]);
+ if (directionalColor) {
+ color = *directionalColor;
}
- break;
- case LED_FUNCTION_ARM_STATE:
- color = ARMING_FLAG(ARMED) ? *getSC(LED_SCOLOR_ARMED) : *getSC(LED_SCOLOR_DISARMED);
- break;
+ break; // stop on first match
+ }
+ break;
- case LED_FUNCTION_BATTERY:
- color = HSV(RED);
- hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120);
- break;
+ case LED_FUNCTION_ARM_STATE:
+ color = ARMING_FLAG(ARMED) ? *getSC(LED_SCOLOR_ARMED) : *getSC(LED_SCOLOR_DISARMED);
+ break;
- case LED_FUNCTION_RSSI:
- color = HSV(RED);
- hOffset += scaleRange(rssi * 100, 0, 1023, -30, 120);
- break;
+ case LED_FUNCTION_BATTERY:
+ color = HSV(RED);
+ hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120);
+ break;
- default:
- break;
+ case LED_FUNCTION_RSSI:
+ color = HSV(RED);
+ hOffset += scaleRange(rssi * 100, 0, 1023, -30, 120);
+ break;
+
+ default:
+ break;
}
if (ledGetOverlayBit(ledConfig, LED_OVERLAY_THROTTLE)) //smooth fade with selected Aux channel of all HSV values from previousColor through color to nextColor
- {
- int centerPWM = (PWM_RANGE_MIN + PWM_RANGE_MAX) / 2;
+ {
+ int centerPWM = (PWM_RANGE_MIN + PWM_RANGE_MAX) / 2;
if (auxInput < centerPWM)
{
color.h = scaleRange(auxInput, PWM_RANGE_MIN, centerPWM, previousColor.h, color.h);
diff --git a/src/main/io/rcsplit.c b/src/main/io/rcsplit.c
index ef61998c7..bf6b8ac64 100644
--- a/src/main/io/rcsplit.c
+++ b/src/main/io/rcsplit.c
@@ -111,7 +111,7 @@ static void rcSplitProcessMode()
argument = RCSPLIT_CTRL_ARGU_INVALID;
break;
}
-
+
if (argument != RCSPLIT_CTRL_ARGU_INVALID) {
sendCtrlCommand(argument);
switchStates[switchIndex].isActivated = true;
diff --git a/src/main/sensors/gyroanalyse.c b/src/main/sensors/gyroanalyse.c
index 8f29c37bf..b680a131b 100644
--- a/src/main/sensors/gyroanalyse.c
+++ b/src/main/sensors/gyroanalyse.c
@@ -8,11 +8,11 @@
*
* Cleanflight 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
+ * 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 Cleanflight. If not, see .
+ * along with Cleanflight. If not, see .
*/
#include
diff --git a/src/main/target/FRSKYF3/target.c b/src/main/target/FRSKYF3/target.c
index 0e9830300..4b6f68df3 100644
--- a/src/main/target/FRSKYF3/target.c
+++ b/src/main/target/FRSKYF3/target.c
@@ -24,14 +24,14 @@
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM1
- DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM2
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM3
- DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM4
- DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM5
- DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM6
- DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM7
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM8
+ DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM1
+ DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM2
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM3
+ DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM4
+ DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM5
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM6
+ DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM7
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM8
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED|TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), // LED
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED|TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), // LED
};
diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h
index 9c06cbc3b..d42e535b1 100644
--- a/src/main/target/FURYF3/target.h
+++ b/src/main/target/FURYF3/target.h
@@ -93,7 +93,7 @@
#define M25P16_SPI_INSTANCE SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
+
#define DEFAULT_FEATURES (FEATURE_OSD)
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#else
@@ -102,11 +102,11 @@
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
-
+
#define SDCARD_DETECT_PIN PB2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
-
+
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h
index d2e584d42..0c9798731 100644
--- a/src/main/target/FURYF4/target.h
+++ b/src/main/target/FURYF4/target.h
@@ -80,9 +80,9 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
- #define DEFAULT_FEATURES FEATURE_OSD
-
+
+ #define DEFAULT_FEATURES FEATURE_OSD
+
#else
#define BARO
diff --git a/src/main/target/KIWIF4/target.c b/src/main/target/KIWIF4/target.c
index b51617197..6e8b25876 100644
--- a/src/main/target/KIWIF4/target.c
+++ b/src/main/target/KIWIF4/target.c
@@ -30,7 +30,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0),
#if defined(PLUMF4) || defined(KIWIF4V2)
- DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 1, 0), //LED
+ DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 1, 0), //LED
#else
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED
#endif
diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h
index ce2130349..a6c55e42e 100644
--- a/src/main/target/KIWIF4/target.h
+++ b/src/main/target/KIWIF4/target.h
@@ -21,7 +21,7 @@
#define TARGET_BOARD_IDENTIFIER "PLUM"
#define USBD_PRODUCT_STRING "PLUMF4"
-#elif defined(KIWIF4V2)
+#elif defined(KIWIF4V2)
#define TARGET_BOARD_IDENTIFIER "KIW2"
#define USBD_PRODUCT_STRING "KIWIF4V2"
@@ -36,7 +36,7 @@
#else
#define LED0_PIN PB5
-#define LED1_PIN PB4
+#define LED1_PIN PB4
#endif
#define BEEPER PA8
diff --git a/src/main/target/KROOZX/config.c b/src/main/target/KROOZX/config.c
index e18f3672e..a08100eb1 100755
--- a/src/main/target/KROOZX/config.c
+++ b/src/main/target/KROOZX/config.c
@@ -33,7 +33,7 @@
#ifdef TARGET_CONFIG
void targetConfiguration(void)
{
- voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
+ voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
barometerConfigMutable()->baro_hardware = 0;
compassConfigMutable()->mag_hardware = 0;
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
diff --git a/src/main/target/KROOZX/initialisation.c b/src/main/target/KROOZX/initialisation.c
index d6b8c009c..fa8310910 100755
--- a/src/main/target/KROOZX/initialisation.c
+++ b/src/main/target/KROOZX/initialisation.c
@@ -23,9 +23,9 @@
void targetPreInit(void)
{
- IO_t osdChSwitch = IOGetByTag(IO_TAG(OSD_CH_SWITCH));
+ IO_t osdChSwitch = IOGetByTag(IO_TAG(OSD_CH_SWITCH));
IOInit(osdChSwitch, OWNER_SYSTEM, 0);
IOConfigGPIO(osdChSwitch, IOCFG_OUT_PP);
- IOLo(osdChSwitch);
+ IOLo(osdChSwitch);
}
diff --git a/src/main/target/KROOZX/target.c b/src/main/target/KROOZX/target.c
index 2151586bf..c98d7c945 100755
--- a/src/main/target/KROOZX/target.c
+++ b/src/main/target/KROOZX/target.c
@@ -34,5 +34,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8
- DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0), // LED_STRIP
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0), // LED_STRIP
};
diff --git a/src/main/target/LUMBAF3/target.c b/src/main/target/LUMBAF3/target.c
index 010110bfd..2044d0054 100644
--- a/src/main/target/LUMBAF3/target.c
+++ b/src/main/target/LUMBAF3/target.c
@@ -26,14 +26,14 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM | TIM_USE_TRANSPONDER, TIMER_INPUT_ENABLED), // PPM IN
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
- DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
+ DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM | TIM_USE_TRANSPONDER, TIMER_INPUT_ENABLED), // PPM IN
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
- DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
- DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
-
- DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, 1), // GPIO TIMER - LED_STRIP
+ DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
+
+ DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, 1), // GPIO TIMER - LED_STRIP
};
diff --git a/src/main/target/LUMBAF3/target.h b/src/main/target/LUMBAF3/target.h
index e7dba2d8f..9f1323d1e 100644
--- a/src/main/target/LUMBAF3/target.h
+++ b/src/main/target/LUMBAF3/target.h
@@ -15,7 +15,7 @@
* along with Cleanflight. If not, see .
*/
-#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
+#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
#define LED0_PIN PB3
#define BEEPER PC15
@@ -42,11 +42,11 @@
#define GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_MPU6000_ALIGN CW90_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_MPU6000_ALIGN CW90_DEG
#define USE_VCP
#define USE_UART1
@@ -70,17 +70,17 @@
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define USE_ADC
#define CURRENT_METER_ADC_PIN PB1
-#define VBAT_ADC_PIN PA0
+#define VBAT_ADC_PIN PA0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-#define LED_STRIP
+#define LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
-#define DEFAULT_FEATURES FEATURE_TELEMETRY
-
+#define DEFAULT_FEATURES FEATURE_TELEMETRY
+
// IO - from schematics
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c
index d29cf723a..9e6249a0b 100644
--- a/src/main/target/MATEKF405/target.c
+++ b/src/main/target/MATEKF405/target.c
@@ -25,16 +25,16 @@
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM
-
- DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4
- DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S3 DMA2_ST4
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM
- DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST5
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6
+ DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S3 DMA2_ST4
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST5
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6
+
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0
};
diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h
index bff65e156..916ed6aa3 100644
--- a/src/main/target/MATEKF405/target.h
+++ b/src/main/target/MATEKF405/target.h
@@ -33,8 +33,8 @@
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
#define MPU6500_CS_PIN PC2
#define MPU6500_SPI_INSTANCE SPI1
@@ -57,8 +57,8 @@
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
-#define SPI3_MISO_PIN PB4
-#define SPI3_MOSI_PIN PB5
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC1
@@ -68,16 +68,16 @@
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
-#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
-#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
-#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
-#define SDCARD_DMA_CHANNEL DMA_Channel_0
+#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
+#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
+#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
+#define SDCARD_DMA_CHANNEL DMA_Channel_0
// *************** OSD *****************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
#define OSD
#define USE_MAX7456
diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c
index c301955d2..0ec676edd 100644
--- a/src/main/target/SITL/target.c
+++ b/src/main/target/SITL/target.c
@@ -272,7 +272,7 @@ void failureMode(failureMode_e mode) {
void indicateFailure(failureMode_e mode, int repeatCount)
{
UNUSED(repeatCount);
- printf("Failure LED flash for: [failureMode]!!! %d\n", mode);
+ printf("Failure LED flash for: [failureMode]!!! %d\n", mode);
}
// Time part
diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h
index d7d39d97b..68a5212b3 100644
--- a/src/main/target/SITL/target.h
+++ b/src/main/target/SITL/target.h
@@ -222,12 +222,12 @@ typedef enum
} FLASH_Status;
typedef struct {
- double timestamp; // in seconds
- double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
- double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
- double imu_orientation_quat[4]; //w, x, y, z
- double velocity_xyz[3]; // m/s, earth frame
- double position_xyz[3]; // meters, NED from origin
+ double timestamp; // in seconds
+ double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
+ double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
+ double imu_orientation_quat[4]; //w, x, y, z
+ double velocity_xyz[3]; // m/s, earth frame
+ double position_xyz[3]; // meters, NED from origin
} fdm_packet;
typedef struct {
float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
diff --git a/src/main/target/SITL/udplink.c b/src/main/target/SITL/udplink.c
index 2a444aad8..2a4a4deaf 100644
--- a/src/main/target/SITL/udplink.c
+++ b/src/main/target/SITL/udplink.c
@@ -13,56 +13,56 @@
#include "udplink.h"
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer) {
- int one = 1;
+ int one = 1;
- if ((link->fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1) {
- return -2;
- }
+ if ((link->fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1) {
+ return -2;
+ }
- setsockopt(link->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); // can multi-bind
- fcntl(link->fd, F_SETFL, fcntl(link->fd, F_GETFL, 0) | O_NONBLOCK); // nonblock
+ setsockopt(link->fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); // can multi-bind
+ fcntl(link->fd, F_SETFL, fcntl(link->fd, F_GETFL, 0) | O_NONBLOCK); // nonblock
- link->isServer = isServer;
- memset(&link->si, 0, sizeof(link->si));
- link->si.sin_family = AF_INET;
- link->si.sin_port = htons(port);
- link->port = port;
+ link->isServer = isServer;
+ memset(&link->si, 0, sizeof(link->si));
+ link->si.sin_family = AF_INET;
+ link->si.sin_port = htons(port);
+ link->port = port;
- if (addr == NULL) {
- link->si.sin_addr.s_addr = htonl(INADDR_ANY);
- }else{
- link->si.sin_addr.s_addr = inet_addr(addr);
- }
+ if (addr == NULL) {
+ link->si.sin_addr.s_addr = htonl(INADDR_ANY);
+ }else{
+ link->si.sin_addr.s_addr = inet_addr(addr);
+ }
- if (isServer) {
- if (bind(link->fd, (const struct sockaddr *)&link->si, sizeof(link->si)) == -1) {
- return -1;
- }
- }
- return 0;
+ if (isServer) {
+ if (bind(link->fd, (const struct sockaddr *)&link->si, sizeof(link->si)) == -1) {
+ return -1;
+ }
+ }
+ return 0;
}
int udpSend(udpLink_t* link, const void* data, size_t size) {
- return sendto(link->fd, data, size, 0, (struct sockaddr *)&link->si, sizeof(link->si));
+ return sendto(link->fd, data, size, 0, (struct sockaddr *)&link->si, sizeof(link->si));
}
int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms) {
- fd_set fds;
- struct timeval tv;
+ fd_set fds;
+ struct timeval tv;
- FD_ZERO(&fds);
- FD_SET(link->fd, &fds);
+ FD_ZERO(&fds);
+ FD_SET(link->fd, &fds);
- tv.tv_sec = timeout_ms / 1000;
- tv.tv_usec = (timeout_ms % 1000) * 1000UL;
+ tv.tv_sec = timeout_ms / 1000;
+ tv.tv_usec = (timeout_ms % 1000) * 1000UL;
- if (select(link->fd+1, &fds, NULL, NULL, &tv) != 1) {
- return -1;
- }
+ if (select(link->fd+1, &fds, NULL, NULL, &tv) != 1) {
+ return -1;
+ }
- socklen_t len;
- int ret;
- ret = recvfrom(link->fd, data, size, 0, (struct sockaddr *)&link->recv, &len);
- return ret;
+ socklen_t len;
+ int ret;
+ ret = recvfrom(link->fd, data, size, 0, (struct sockaddr *)&link->recv, &len);
+ return ret;
}
diff --git a/src/main/target/stm32f1xx_hal_conf.h b/src/main/target/stm32f1xx_hal_conf.h
index d44641067..2f5a9c23f 100644
--- a/src/main/target/stm32f1xx_hal_conf.h
+++ b/src/main/target/stm32f1xx_hal_conf.h
@@ -127,8 +127,8 @@
/**
* @brief This is the HAL system configuration section
*/
-#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
-#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */
+#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1