From ed6a4a4769c66d96bd3446f3a2385d0fb7160cdb Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Fri, 15 Nov 2024 16:07:25 -0600 Subject: [PATCH] duplicate emptyline removal (#14027) * trailing space removal Co-authored-by: Petr Ledvina * deduplicate empty lines --------- Co-authored-by: Petr Ledvina Co-authored-by: Mark Haslinghuis --- src/main/blackbox/blackbox.c | 2 -- src/main/blackbox/blackbox_encoding.c | 3 --- src/main/blackbox/blackbox_io.c | 1 - src/main/cli/cli.c | 8 ------ src/main/cli/settings.c | 1 - src/main/cli/settings.h | 4 --- src/main/cms/cms.c | 1 - src/main/cms/cms_menu_blackbox.c | 1 - src/main/cms/cms_menu_firmware.c | 1 - src/main/cms/cms_menu_imu.c | 1 - src/main/cms/cms_menu_main.c | 1 - src/main/common/color.h | 1 - src/main/common/crc.c | 1 - src/main/common/explog_approx.c | 1 - src/main/common/filter.c | 9 ------- src/main/common/gps_conversion.c | 1 - src/main/common/huffman.c | 1 - src/main/common/maths.h | 1 - src/main/common/printf.c | 1 - src/main/common/printf_serial.c | 2 -- src/main/common/printf_serial.h | 1 - src/main/common/pwl.c | 1 - src/main/common/pwl.h | 1 - src/main/common/sdft.c | 9 ------- src/main/common/sensor_alignment.c | 1 - src/main/common/streambuf.c | 1 - src/main/common/strtol.c | 1 - src/main/common/utils.h | 3 --- src/main/config/config_eeprom.c | 2 -- src/main/config/config_streamer.c | 1 - src/main/config/feature.c | 1 - src/main/config/simplified_tuning.c | 1 - src/main/drivers/accgyro/accgyro_mpu.c | 1 - src/main/drivers/accgyro/accgyro_spi_bmi160.c | 4 --- src/main/drivers/accgyro/accgyro_spi_bmi270.c | 1 - src/main/drivers/accgyro/accgyro_spi_icm20649.c | 2 -- src/main/drivers/accgyro/accgyro_spi_icm426xx.c | 1 - src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c | 2 -- src/main/drivers/accgyro/accgyro_spi_mpu6000.c | 1 - src/main/drivers/accgyro/accgyro_spi_mpu9250.c | 1 - src/main/drivers/accgyro/accgyro_virtual.c | 1 - src/main/drivers/accgyro/gyro_sync.c | 1 - src/main/drivers/accgyro/legacy/accgyro_l3g4200d.c | 1 - .../drivers/accgyro/legacy/accgyro_lsm303dlhc.h | 1 - src/main/drivers/barometer/barometer_2smpb_02b.c | 1 - src/main/drivers/barometer/barometer_bmp280.c | 1 - src/main/drivers/barometer/barometer_bmp388.c | 2 -- src/main/drivers/barometer/barometer_dps310.c | 2 -- src/main/drivers/barometer/barometer_ms5611.c | 1 - src/main/drivers/barometer/barometer_qmp6988.c | 2 -- src/main/drivers/barometer/barometer_virtual.c | 2 -- src/main/drivers/bus.c | 2 -- src/main/drivers/bus_octospi.h | 2 -- src/main/drivers/bus_quadspi.c | 1 - src/main/drivers/bus_quadspi.h | 2 -- src/main/drivers/bus_quadspi_impl.h | 1 - src/main/drivers/bus_spi.h | 1 - src/main/drivers/compass/compass_virtual.c | 1 - src/main/drivers/display_canvas.h | 1 - src/main/drivers/dma.h | 1 - src/main/drivers/dshot.h | 1 - src/main/drivers/dshot_bitbang_decode.c | 2 -- src/main/drivers/dshot_dpwm.h | 1 - src/main/drivers/flash/flash.c | 1 - src/main/drivers/flash/flash.h | 2 -- src/main/drivers/flash/flash_m25p16.c | 4 --- src/main/drivers/flash/flash_w25n.c | 4 --- src/main/drivers/flash/flash_w25q128fv.c | 5 ---- src/main/drivers/inverter.c | 1 - src/main/drivers/io_def.h | 1 - src/main/drivers/io_def_generated.h | 2 -- src/main/drivers/light_ws2811strip.c | 1 - src/main/drivers/max7456.c | 1 - src/main/drivers/motor.h | 1 - src/main/drivers/nvic.h | 1 - src/main/drivers/pin_pull_up_down.c | 1 - src/main/drivers/pwm_output_dshot_shared.c | 3 --- src/main/drivers/rangefinder/rangefinder_hcsr04.c | 1 - src/main/drivers/rx/rx_nrf24l01.h | 2 -- src/main/drivers/rx/rx_pwm.c | 1 - src/main/drivers/rx/rx_sx1280.c | 2 -- src/main/drivers/rx/rx_xn297.c | 2 -- src/main/drivers/sdcard_spi.c | 3 --- src/main/drivers/sdmmc_sdio.h | 2 -- src/main/drivers/serial.c | 1 - src/main/drivers/serial_escserial.c | 7 ----- src/main/drivers/serial_impl.c | 2 -- src/main/drivers/serial_impl.h | 1 - src/main/drivers/serial_pinconfig.c | 1 - src/main/drivers/serial_softserial.c | 2 -- src/main/drivers/serial_uart.c | 1 - src/main/drivers/system.c | 1 - src/main/drivers/transponder_ir.h | 3 --- src/main/drivers/transponder_ir_arcitimer.c | 2 -- src/main/drivers/transponder_ir_arcitimer.h | 2 -- src/main/drivers/vtx_common.c | 1 - src/main/drivers/vtx_common.h | 1 - src/main/drivers/vtx_rtc6705.h | 1 - src/main/drivers/vtx_rtc6705_soft_spi.c | 2 -- src/main/drivers/vtx_rtc6705_soft_spi.h | 1 - src/main/drivers/vtx_table.c | 1 - src/main/drivers/vtx_table.h | 1 - src/main/fc/core.c | 3 --- src/main/fc/init.c | 2 -- src/main/flight/dyn_notch_filter.c | 1 - src/main/flight/imu.c | 2 -- src/main/flight/mixer_init.c | 1 - src/main/flight/mixer_tricopter.c | 1 - src/main/flight/mixer_tricopter.h | 1 - src/main/flight/pid.c | 1 - src/main/flight/pid_init.c | 1 - src/main/flight/rpm_filter.c | 2 -- src/main/flight/servos.c | 4 --- src/main/flight/servos_tricopter.c | 1 - src/main/io/beeper.c | 3 --- src/main/io/dashboard.c | 4 --- src/main/io/displayport_crsf.c | 1 - src/main/io/displayport_frsky_osd.c | 1 - src/main/io/displayport_srxl.c | 1 - src/main/io/flashfs.c | 3 --- src/main/io/frsky_osd.c | 2 -- src/main/io/gimbal_control.c | 1 - src/main/io/gps.c | 1 - src/main/io/gps.h | 1 - src/main/io/rcdevice.c | 1 - src/main/io/rcdevice_cam.c | 2 -- src/main/io/serial.c | 2 -- src/main/io/serial_4way.c | 8 ------ src/main/io/serial_4way_stk500v2.c | 4 --- src/main/io/serial_resource.c | 2 -- src/main/io/spektrum_rssi.h | 1 - src/main/io/spektrum_vtx_control.c | 1 - src/main/io/spektrum_vtx_control.h | 3 --- src/main/io/usb_cdc_hid.c | 1 - src/main/io/vtx.c | 1 - src/main/io/vtx_control.c | 2 -- src/main/io/vtx_rtc6705.c | 1 - src/main/io/vtx_smartaudio.c | 10 -------- src/main/io/vtx_smartaudio.h | 1 - src/main/msc/usbd_storage_emfat.c | 1 - src/main/msc/usbd_storage_sd_spi.c | 1 - src/main/msc/usbd_storage_sdio.c | 1 - src/main/msp/msp.c | 5 ---- src/main/msp/msp.h | 1 - src/main/msp/msp_box.c | 1 - src/main/msp/msp_protocol.h | 1 - src/main/osd/osd.c | 2 -- src/main/osd/osd.h | 2 -- src/main/osd/osd_elements.c | 1 - src/main/pg/adc.c | 1 - src/main/pg/gyrodev.h | 1 - src/main/pg/motor.c | 1 - src/main/pg/pg_ids.h | 4 --- src/main/pg/sdio.c | 1 - src/main/rx/cc2500_frsky_shared.h | 1 - src/main/rx/cc2500_frsky_x.c | 1 - src/main/rx/crsf.c | 1 - src/main/rx/crsf.h | 1 - src/main/rx/cyrf6936_spektrum.c | 1 - src/main/rx/expresslrs.c | 2 -- src/main/rx/fport.c | 3 --- src/main/rx/ghst.c | 1 - src/main/rx/ghst_protocol.h | 1 - src/main/rx/ibus.c | 6 ----- src/main/rx/jetiexbus.c | 5 ---- src/main/rx/msp.c | 1 - src/main/rx/msp_override.c | 1 - src/main/rx/nrf24_h8_3d.c | 2 -- src/main/rx/nrf24_inav.c | 1 - src/main/rx/nrf24_syma.c | 1 - src/main/rx/rc_stats.c | 1 - src/main/rx/rx.c | 1 - src/main/rx/rx.h | 1 - src/main/rx/spektrum.c | 2 -- src/main/rx/spektrum.h | 1 - src/main/rx/srxl2.c | 4 --- src/main/rx/sumh.c | 1 - src/main/rx/xbus.c | 3 --- src/main/sensors/acceleration_init.c | 1 - src/main/sensors/acceleration_init.h | 1 - src/main/sensors/barometer.c | 1 - src/main/sensors/current.c | 1 - src/main/sensors/current.h | 3 --- src/main/sensors/gyro.c | 1 - src/main/sensors/gyro_init.c | 2 -- src/main/sensors/initialisation.c | 1 - src/main/sensors/voltage.c | 5 ---- src/main/sensors/voltage.h | 3 --- src/main/target/common_post.h | 2 -- src/main/target/common_pre.h | 2 -- src/main/target/serial_post.h | 5 ---- src/main/telemetry/crsf.c | 2 -- src/main/telemetry/hott.c | 1 - src/main/telemetry/hott.h | 3 --- src/main/telemetry/ibus.c | 9 ------- src/main/telemetry/ibus_shared.c | 8 ------ src/main/telemetry/ibus_shared.h | 1 - src/main/telemetry/jetiexbus.c | 3 --- src/main/telemetry/ltm.c | 1 - src/main/telemetry/mavlink.c | 3 --- src/main/telemetry/msp_shared.c | 1 - src/main/telemetry/srxl.c | 3 --- src/platform/APM32/bus_spi_apm32.c | 1 - src/platform/APM32/dshot_bitbang.c | 2 -- src/platform/APM32/eint_apm32.c | 2 -- src/platform/APM32/pwm_output_apm32.c | 1 - src/platform/APM32/pwm_output_dshot_apm32.c | 1 - src/platform/APM32/serial_uart_apm32.c | 2 -- src/platform/APM32/startup/apm32f4xx_dal_cfg.h | 1 - src/platform/APM32/startup/system_apm32f4xx.h | 1 - src/platform/APM32/timer_apm32f4xx.c | 2 -- src/platform/APM32/transponder_ir_io_apm32.c | 2 -- src/platform/APM32/usb/msc/usbd_msc_descriptor.c | 1 - src/platform/APM32/usb/usbd_board_apm32f4.c | 2 -- src/platform/APM32/usb/vcp/usbd_cdc_vcp.c | 1 - src/platform/APM32/usb/vcp/usbd_cdc_vcp.h | 1 - src/platform/AT32/adc_at32f43x.c | 4 --- src/platform/AT32/bus_i2c_atbsp.c | 1 - src/platform/AT32/bus_i2c_atbsp_init.c | 1 - src/platform/AT32/bus_spi_at32bsp.c | 1 - src/platform/AT32/dshot_bitbang.c | 1 - src/platform/AT32/light_ws2811strip_at32f43x.c | 2 -- src/platform/AT32/pwm_output_at32bsp.c | 1 - src/platform/AT32/pwm_output_dshot.c | 2 -- src/platform/AT32/serial_uart_at32bsp.c | 1 - src/platform/AT32/serial_uart_at32f43x.c | 1 - src/platform/AT32/startup/at32f435_437.h | 1 - src/platform/AT32/startup/at32f435_437_conf.h | 1 - src/platform/AT32/target/AT32F435G/target.h | 1 - src/platform/AT32/target/AT32F435M/target.h | 1 - src/platform/AT32/timer_at32f43x.c | 1 - src/platform/AT32/timer_def.h | 2 -- src/platform/AT32/usbd_msc_mem.h | 1 - src/platform/SITL/sitl.c | 2 -- src/platform/SITL/target/SITL/target.h | 1 - src/platform/STM32/adc_stm32f7xx.c | 1 - src/platform/STM32/bus_octospi_stm32h7xx.c | 7 ----- src/platform/STM32/bus_quadspi_hal.c | 5 ---- src/platform/STM32/bus_spi_ll.c | 1 - src/platform/STM32/bus_spi_stdperiph.c | 2 -- src/platform/STM32/dshot_bitbang.c | 2 -- src/platform/STM32/exti.c | 2 -- src/platform/STM32/pwm_output_dshot.c | 3 --- src/platform/STM32/pwm_output_dshot_hal.c | 1 - src/platform/STM32/sdio_f4xx.c | 30 ---------------------- src/platform/STM32/sdio_f7xx.c | 30 ---------------------- src/platform/STM32/serial_uart_hal.c | 3 --- src/platform/STM32/serial_usb_vcp.c | 2 -- src/platform/STM32/startup/stm32f4xx_hal_conf.h | 2 -- src/platform/STM32/startup/stm32f7xx_hal_conf.h | 1 - src/platform/STM32/startup/stm32g4xx_hal_conf.h | 1 - src/platform/STM32/startup/stm32h5xx_hal_conf.h | 2 -- src/platform/STM32/startup/stm32h7xx_hal_conf.h | 4 --- src/platform/STM32/startup/system_stm32f4xx.c | 2 -- src/platform/STM32/startup/system_stm32g4xx.h | 1 - src/platform/STM32/startup/system_stm32h5xx.c | 1 - src/platform/STM32/startup/system_stm32h5xx.h | 3 --- src/platform/STM32/startup/system_stm32h7xx.c | 5 ---- src/platform/STM32/startup/system_stm32h7xx.h | 1 - src/platform/STM32/system_stm32f4xx.c | 1 - src/platform/STM32/system_stm32f7xx.c | 1 - src/platform/STM32/system_stm32g4xx.c | 1 - src/platform/STM32/system_stm32h7xx.c | 3 --- src/platform/STM32/target/STM32H563/target.h | 2 -- src/platform/STM32/target/STM32H725/target.h | 1 - src/platform/STM32/timer_def.h | 1 - src/platform/STM32/timer_stm32f4xx.c | 2 -- src/platform/STM32/timer_stm32f7xx.c | 1 - src/platform/STM32/timer_stm32g4xx.c | 1 - src/platform/STM32/timer_stm32h7xx.c | 1 - src/platform/STM32/transponder_ir_io_hal.c | 2 -- src/platform/STM32/usbd_msc_desc.c | 11 -------- src/platform/STM32/usbd_msc_desc.h | 4 --- src/platform/STM32/vcp/hw_config.c | 2 -- src/platform/STM32/vcp/stm32_it.c | 3 --- src/platform/STM32/vcp_hal/usbd_cdc_interface.c | 2 -- src/platform/STM32/vcp_hal/usbd_conf_stm32f7xx.c | 2 -- src/platform/STM32/vcp_hal/usbd_conf_stm32h7xx.c | 1 - src/platform/STM32/vcpf4/usb_bsp.c | 1 - src/platform/STM32/vcpf4/usb_cdc_hid.c | 1 - src/platform/STM32/vcpf4/usb_conf.h | 8 ------ src/platform/STM32/vcpf4/usbd_cdc_vcp.c | 4 --- src/platform/STM32/vcpf4/usbd_cdc_vcp.h | 1 - src/platform/STM32/vcpf4/usbd_conf.h | 3 --- src/platform/STM32/vcpf4/usbd_desc.c | 11 -------- src/platform/STM32/vcpf4/usbd_desc.h | 4 --- src/platform/STM32/vcpf4/usbd_usr.c | 5 ---- src/test/unit/target.h | 1 - src/test/unit/unittest_macros.h | 1 - 289 files changed, 629 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 97ff5bc5f..044bbc090 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -91,7 +91,6 @@ #include "sensors/gyro_init.h" #include "sensors/rangefinder.h" - #ifdef USE_FLASH_TEST_PRBS void checkFlashStart(void); void checkFlashStop(void); @@ -337,7 +336,6 @@ typedef enum BlackboxState { BLACKBOX_STATE_ERASED } BlackboxState; - typedef struct blackboxMainState_s { uint32_t time; diff --git a/src/main/blackbox/blackbox_encoding.c b/src/main/blackbox/blackbox_encoding.c index 200c00b5d..dbec91146 100644 --- a/src/main/blackbox/blackbox_encoding.c +++ b/src/main/blackbox/blackbox_encoding.c @@ -34,7 +34,6 @@ #include "common/encoding.h" #include "common/printf.h" - static void _putc(void *p, char c) { (void)p; @@ -46,7 +45,6 @@ static int blackboxPrintfv(const char *fmt, va_list va) return tfp_format(NULL, _putc, fmt, va); } - //printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!) int blackboxPrintf(const char *fmt, ...) { @@ -271,7 +269,6 @@ int blackboxWriteTag2_3SVariable(int32_t *values) BYTES_4 = 3 }; - /* * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes * below: diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 5284bf4d2..b981c2840 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -322,7 +322,6 @@ bool blackboxDeviceOpen(void) * = (looptime_ns * 3) / 500 */ - switch (baudRateIndex) { case BAUD_1000000: case BAUD_1500000: diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 455856fb7..1dff69595 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -447,7 +447,6 @@ void cliPrintf(const char *format, ...) va_end(va); } - void cliPrintLinef(const char *format, ...) { va_list va; @@ -645,7 +644,6 @@ static void printValuePointer(const char *cmdName, const clivalue_t *var, const } } - static bool valuePtrEqualsDefault(const clivalue_t *var, const void *ptr, const void *ptrDefault) { bool result = true; @@ -763,7 +761,6 @@ static uint8_t getRateProfileIndexToUse(void) return rateProfileIndexToUse == CURRENT_PROFILE_INDEX ? getCurrentControlRateProfileIndex() : rateProfileIndexToUse; } - static uint16_t getValueOffset(const clivalue_t *value) { switch (value->type & VALUE_SECTION_MASK) { @@ -1317,7 +1314,6 @@ static void cliSerial(const char *cmdName, char *cmdline) serialPortConfig_t portConfig; memset(&portConfig, 0 , sizeof(portConfig)); - uint8_t validArgumentCount = 0; const char *ptr = cmdline; @@ -1534,7 +1530,6 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline) index++; } - for (unsigned i = 0; i < ARRAYLEN(ports); i++) { if (findSerialPortIndexByIdentifier(ports[i].id) < 0) { cliPrintLinef("Invalid port%d %d", i + 1, ports[i].id); @@ -3530,7 +3525,6 @@ static void printMap(dumpFlags_t dumpMask, const rxConfig_t *rxConfig, const rxC cliDumpPrintLinef(dumpMask, equalsDefault, formatMap, buf); } - static void cliMap(const char *cmdName, char *cmdline) { uint32_t i; @@ -3696,7 +3690,6 @@ static void cliDumpGyroRegisters(const char *cmdName, char *cmdline) } #endif - static int parseOutputIndex(const char *cmdName, char *pch, bool allowAllEscs) { int outputIndex = atoi(pch); @@ -6189,7 +6182,6 @@ static void cliResource(const char *cmdName, char *cmdline) #ifdef USE_DSHOT_TELEMETRY - static void cliDshotTelemetryInfo(const char *cmdName, char *cmdline) { UNUSED(cmdName); diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index bc2fa391a..507e2767e 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -137,7 +137,6 @@ #include "settings.h" - // Sensor names (used in lookup tables for *_hardware settings and in status command output) // sync with accelerationSensor_e const char * const lookupTableAccHardware[] = { diff --git a/src/main/cli/settings.h b/src/main/cli/settings.h index 55ee1f621..b67664a0e 100644 --- a/src/main/cli/settings.h +++ b/src/main/cli/settings.h @@ -24,7 +24,6 @@ #include #include "pg/pg.h" - typedef enum { TABLE_OFF_ON = 0, TABLE_UNIT, @@ -158,7 +157,6 @@ typedef struct lookupTableEntry_s { const uint8_t valueCount; } lookupTableEntry_t; - #define VALUE_TYPE_OFFSET 0 #define VALUE_SECTION_OFFSET 3 #define VALUE_MODE_OFFSET 5 @@ -186,7 +184,6 @@ typedef enum { MODE_STRING = (4 << VALUE_MODE_OFFSET), } cliValueFlag_e; - #define VALUE_TYPE_MASK (0x07) #define VALUE_SECTION_MASK (0x18) #define VALUE_MODE_MASK (0xE0) @@ -244,7 +241,6 @@ typedef struct clivalue_s { uint16_t offset; } PTR_PACKING clivalue_t; - extern const lookupTableEntry_t lookupTables[]; extern const uint16_t valueTableEntryCount; diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 1e51f7d11..af8f84622 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -786,7 +786,6 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) } } - // Highlight values overridden by sliders if (rowSliderOverride(p->flags)) { displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, 'S'); diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 0a55c4bb5..8fee46608 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -220,7 +220,6 @@ static const void *cmsx_StorageDevice(displayPort_t *pDisplay, const void *ptr) } #endif //USE_USB_MSC - static const void *cmsx_Blackbox_onEnter(displayPort_t *pDisp) { UNUSED(pDisp); diff --git a/src/main/cms/cms_menu_firmware.c b/src/main/cms/cms_menu_firmware.c index 776fbe2ef..25073a93a 100644 --- a/src/main/cms/cms_menu_firmware.c +++ b/src/main/cms/cms_menu_firmware.c @@ -53,7 +53,6 @@ #include "cms_menu_firmware.h" - // Calibration #define CALIBRATION_STATUS_MAX_LENGTH 6 diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index e40d118bb..aa5929bf6 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -747,7 +747,6 @@ static CMS_Menu cmsx_menuProfileOther = { .entries = cmsx_menuProfileOtherEntries, }; - static uint16_t gyroConfig_gyro_lpf1_static_hz; static uint16_t gyroConfig_gyro_lpf2_static_hz; static uint16_t gyroConfig_gyro_soft_notch_hz_1; diff --git a/src/main/cms/cms_menu_main.c b/src/main/cms/cms_menu_main.c index b43cf8d38..7543aa011 100644 --- a/src/main/cms/cms_menu_main.c +++ b/src/main/cms/cms_menu_main.c @@ -129,7 +129,6 @@ static const void *cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr) return NULL; } - #ifdef USE_BATTERY_CONTINUE #define SETUP_POPUP_MAX_ENTRIES 2 // Increase as new entries are added #else diff --git a/src/main/common/color.h b/src/main/common/color.h index 3eb7a53cf..cc44b0d06 100644 --- a/src/main/common/color.h +++ b/src/main/common/color.h @@ -20,7 +20,6 @@ #pragma once - typedef enum { RGB_RED = 0, RGB_GREEN, diff --git a/src/main/common/crc.c b/src/main/common/crc.c index f43b75ee7..771cbaeab 100644 --- a/src/main/common/crc.c +++ b/src/main/common/crc.c @@ -26,7 +26,6 @@ #include "streambuf.h" - uint16_t crc16_ccitt(uint16_t crc, unsigned char a) { crc ^= (uint16_t)a << 8; diff --git a/src/main/common/explog_approx.c b/src/main/common/explog_approx.c index a77af26dc..b2eae4468 100644 --- a/src/main/common/explog_approx.c +++ b/src/main/common/explog_approx.c @@ -82,7 +82,6 @@ float log_approx(float val) valu.i = (valu.i & 0x7FFFFF) | 0x3F800000; x = valu.f; - /* Generated in Sollya using: > f = remez(log(x)-(x-1)*log(2), [|1,(x-1)*(x-2), (x-1)*(x-2)*x, (x-1)*(x-2)*x*x, diff --git a/src/main/common/filter.c b/src/main/common/filter.c index c159930b7..1fad9d791 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -42,7 +42,6 @@ float nullFilterApply(filter_t *filter, float input) return input; } - // PT1 Low Pass filter FAST_CODE_NOINLINE float pt1FilterGain(float f_cut, float dT) @@ -79,7 +78,6 @@ FAST_CODE float pt1FilterApply(pt1Filter_t *filter, float input) return filter->state; } - // PT2 Low Pass filter FAST_CODE float pt2FilterGain(float f_cut, float dT) @@ -118,7 +116,6 @@ FAST_CODE float pt2FilterApply(pt2Filter_t *filter, float input) return filter->state; } - // PT3 Low Pass filter FAST_CODE float pt3FilterGain(float f_cut, float dT) @@ -159,7 +156,6 @@ FAST_CODE float pt3FilterApply(pt3Filter_t *filter, float input) return filter->state; } - // Biquad filter // get notch filter Q given center frequency (f0) and lower cutoff frequency (f1) @@ -274,7 +270,6 @@ FAST_CODE float biquadFilterApply(biquadFilter_t *filter, float input) return result; } - // Phase Compensator (Lead-Lag-Compensator) void phaseCompInit(phaseComp_t *filter, const float centerFreqHz, const float centerPhaseDeg, const uint32_t looptimeUs) @@ -315,7 +310,6 @@ FAST_CODE float phaseCompApply(phaseComp_t *filter, const float input) return result; } - // Slew filter with limit void slewFilterInit(slewFilter_t *filter, float slewLimit, float threshold) @@ -341,7 +335,6 @@ FAST_CODE float slewFilterApply(slewFilter_t *filter, float input) return filter->state; } - // Moving average void laggedMovingAverageInit(laggedMovingAverage_t *filter, uint16_t windowSize, float *buf) @@ -369,7 +362,6 @@ FAST_CODE float laggedMovingAverageUpdate(laggedMovingAverage_t *filter, float i return filter->movingSum / denom; } - // Simple fixed-point lowpass filter based on integer math void simpleLPFilterInit(simpleLowpassFilter_t *filter, int32_t beta, int32_t fpShift) @@ -388,7 +380,6 @@ int32_t simpleLPFilterUpdate(simpleLowpassFilter_t *filter, int32_t newVal) return result; } - // Mean accumulator void meanAccumulatorInit(meanAccumulator_t *filter) diff --git a/src/main/common/gps_conversion.c b/src/main/common/gps_conversion.c index fda6bf974..33fe1778f 100644 --- a/src/main/common/gps_conversion.c +++ b/src/main/common/gps_conversion.c @@ -27,7 +27,6 @@ #ifdef USE_GPS - #define DIGIT_TO_VAL(_x) (_x - '0') uint32_t GPS_coord_to_degrees(const char* coordinateString) { diff --git a/src/main/common/huffman.c b/src/main/common/huffman.c index a21a48094..9f4097b1c 100644 --- a/src/main/common/huffman.c +++ b/src/main/common/huffman.c @@ -24,7 +24,6 @@ #include "huffman.h" - int huffmanEncodeBuf(uint8_t *outBuf, int outBufLen, const uint8_t *inBuf, int inLen, const huffmanTable_t *huffmanTable) { int ret = 0; diff --git a/src/main/common/maths.h b/src/main/common/maths.h index f071a3b57..e0345fdf4 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -43,7 +43,6 @@ #define DEGREES_TO_RADIANS(angle) ((angle) * RAD) #define RADIANS_TO_DEGREES(angle) ((angle) / RAD) - #define CM_S_TO_KM_H(centimetersPerSecond) ((centimetersPerSecond) * 36 / 1000) #define CM_S_TO_MPH(centimetersPerSecond) ((centimetersPerSecond) * 10000 / 5080 / 88) diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 4c65e293e..ce40994d8 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -44,7 +44,6 @@ #include "typeconversion.h" #endif - #ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT putcf stdout_putf; diff --git a/src/main/common/printf_serial.c b/src/main/common/printf_serial.c index 6be8bc204..35876d2de 100644 --- a/src/main/common/printf_serial.c +++ b/src/main/common/printf_serial.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include #include @@ -60,7 +59,6 @@ static void _putc(void *p, char c) serialWrite(printfSerialPort, c); } - void printfSerialInit(void) { init_printf(NULL, _putc); diff --git a/src/main/common/printf_serial.h b/src/main/common/printf_serial.h index db47a5be6..fc6bc6d1a 100644 --- a/src/main/common/printf_serial.h +++ b/src/main/common/printf_serial.h @@ -18,7 +18,6 @@ * If not, see . */ - struct serialPort_s; void printfSerialInit(void); diff --git a/src/main/common/pwl.c b/src/main/common/pwl.c index 6c2177af7..50d097596 100644 --- a/src/main/common/pwl.c +++ b/src/main/common/pwl.c @@ -23,7 +23,6 @@ #include "pwl.h" - void pwlInitialize(pwl_t *pwl, float *yValues, int numPoints, float xMin, float xMax) { pwl->yValues = yValues; pwl->numPoints = numPoints; diff --git a/src/main/common/pwl.h b/src/main/common/pwl.h index 458d21321..9a767d50d 100644 --- a/src/main/common/pwl.h +++ b/src/main/common/pwl.h @@ -23,7 +23,6 @@ #include "utils.h" - #define PWL_DECLARE(name, size, xMinV, xMaxV) \ STATIC_ASSERT((xMinV) < (xMaxV), "xMinV must be less than xMaxV"); \ STATIC_ASSERT((size) > 1, "size must be more than 1"); \ diff --git a/src/main/common/sdft.c b/src/main/common/sdft.c index 14bb3f0b6..33afa0726 100644 --- a/src/main/common/sdft.c +++ b/src/main/common/sdft.c @@ -35,7 +35,6 @@ static FAST_DATA_ZERO_INIT complex_t twiddle[SDFT_BIN_COUNT]; static void applySqrt(const sdft_t *sdft, float *data); static void updateEdges(sdft_t *sdft, const float value, const int batchIdx); - void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numBatches) { if (!isInitialized) { @@ -65,7 +64,6 @@ void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numB } } - // Add new sample to frequency spectrum FAST_CODE void sdftPush(sdft_t *sdft, const float sample) { @@ -81,7 +79,6 @@ FAST_CODE void sdftPush(sdft_t *sdft, const float sample) updateEdges(sdft, delta, 0); } - // Add new sample to frequency spectrum in parts FAST_CODE void sdftPushBatch(sdft_t *sdft, const float sample, const int batchIdx) { @@ -105,7 +102,6 @@ FAST_CODE void sdftPushBatch(sdft_t *sdft, const float sample, const int batchId updateEdges(sdft, delta, batchIdx); } - // Get squared magnitude of frequency spectrum FAST_CODE void sdftMagSq(const sdft_t *sdft, float *output) { @@ -119,7 +115,6 @@ FAST_CODE void sdftMagSq(const sdft_t *sdft, float *output) } } - // Get magnitude of frequency spectrum (slower) FAST_CODE void sdftMagnitude(const sdft_t *sdft, float *output) { @@ -127,7 +122,6 @@ FAST_CODE void sdftMagnitude(const sdft_t *sdft, float *output) applySqrt(sdft, output); } - // Get squared magnitude of frequency spectrum with Hann window applied // Hann window in frequency domain: X[k] = -0.25 * X[k-1] +0.5 * X[k] -0.25 * X[k+1] FAST_CODE void sdftWinSq(const sdft_t *sdft, float *output) @@ -164,7 +158,6 @@ FAST_CODE void sdftWinSq(const sdft_t *sdft, float *output) output[sdft->endBin] = re * re + im * im; } - // Get magnitude of frequency spectrum with Hann window applied (slower) FAST_CODE void sdftWindow(const sdft_t *sdft, float *output) { @@ -172,7 +165,6 @@ FAST_CODE void sdftWindow(const sdft_t *sdft, float *output) applySqrt(sdft, output); } - // Apply square root to the whole sdft range static FAST_CODE void applySqrt(const sdft_t *sdft, float *data) { @@ -181,7 +173,6 @@ static FAST_CODE void applySqrt(const sdft_t *sdft, float *data) } } - // Needed for proper windowing at the edges of active range static FAST_CODE void updateEdges(sdft_t *sdft, const float value, const int batchIdx) { diff --git a/src/main/common/sensor_alignment.c b/src/main/common/sensor_alignment.c index 47267c319..e19365cfc 100644 --- a/src/main/common/sensor_alignment.c +++ b/src/main/common/sensor_alignment.c @@ -39,7 +39,6 @@ void buildRotationMatrixFromAngles(matrix33_t *rm, const sensorAlignment_t *rpy) buildRotationMatrix(rm, &rotationAngles); } - void buildAlignmentFromStandardAlignment(sensorAlignment_t* rpy, sensor_align_e stdAlignment) { if (stdAlignment == ALIGN_CUSTOM || stdAlignment == ALIGN_DEFAULT) { diff --git a/src/main/common/streambuf.c b/src/main/common/streambuf.c index 74fdf2a08..0268b6db3 100644 --- a/src/main/common/streambuf.c +++ b/src/main/common/streambuf.c @@ -65,7 +65,6 @@ void sbufWriteU32BigEndian(sbuf_t *dst, uint32_t val) sbufWriteU8(dst, (uint8_t)val); } - void sbufFill(sbuf_t *dst, uint8_t data, int len) { memset(dst->ptr, data, len); diff --git a/src/main/common/strtol.c b/src/main/common/strtol.c index b14ce8d36..1d1e0413f 100644 --- a/src/main/common/strtol.c +++ b/src/main/common/strtol.c @@ -19,7 +19,6 @@ */ - #include #include diff --git a/src/main/common/utils.h b/src/main/common/utils.h index 726640b9f..3ec18bdd0 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -79,8 +79,6 @@ static inline int popcount(unsigned x) { return __builtin_popcount(x); } static inline int popcount32(uint32_t x) { return __builtin_popcount(x); } static inline int popcount64(uint64_t x) { return __builtin_popcountll(x); } - - /* * https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ * Return (v ? floor(log2(v)) : 0) when 0 <= v < 1<<[8, 16, 32, 64]. @@ -121,7 +119,6 @@ static inline void memcpy_fn ( void * destination, const void * source, size_t void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("memcpy"); #endif - #endif #if __GNUC__ > 6 diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index d625e5942..f77586d3d 100644 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -153,7 +153,6 @@ MMFLASH_CODE_NOINLINE void saveEEPROMToMemoryMappedFlash(void) } #endif - #elif defined(CONFIG_IN_SDCARD) enum { @@ -477,7 +476,6 @@ static bool writeSettingsToEEPROM(void) .flags = 0, }; - record.flags |= CR_CLASSICATION_SYSTEM; config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record)); crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record)); diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index c9c528576..fc5ab2569 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -36,7 +36,6 @@ uint8_t eepromData[EEPROM_SIZE]; #endif #endif - #if !defined(FLASH_PAGE_SIZE) #error "Flash page size not defined for target." #endif diff --git a/src/main/config/feature.c b/src/main/config/feature.c index 06b013155..ce3b76014 100644 --- a/src/main/config/feature.c +++ b/src/main/config/feature.c @@ -28,7 +28,6 @@ #include "pg/pg.h" #include "pg/pg_ids.h" - PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 1); PG_RESET_TEMPLATE(featureConfig_t, featureConfig, diff --git a/src/main/config/simplified_tuning.c b/src/main/config/simplified_tuning.c index 024c2f792..62dd374e2 100644 --- a/src/main/config/simplified_tuning.c +++ b/src/main/config/simplified_tuning.c @@ -115,7 +115,6 @@ void applySimplifiedTuningGyroFilters(gyroConfig_t *gyroConfig) } } - void applySimplifiedTuning(pidProfile_t *pidProfile, gyroConfig_t *gyroConfig) { applySimplifiedTuningPids(pidProfile); diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 0c87bba16..4febfe238 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -214,7 +214,6 @@ bool mpuGyroRead(gyroDev_t *gyro) return true; } - #ifdef USE_SPI_GYRO bool mpuAccReadSPI(accDev_t *acc) { diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index a48cab1cc..108efcbbd 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -364,7 +364,6 @@ static bool bmi160AccRead(accDev_t *acc) return true; } - static bool bmi160GyroRead(gyroDev_t *gyro) { extDevice_t *dev = &gyro->dev; @@ -438,7 +437,6 @@ static bool bmi160GyroRead(gyroDev_t *gyro) return true; } - void bmi160SpiGyroInit(gyroDev_t *gyro) { extDevice_t *dev = &gyro->dev; @@ -454,7 +452,6 @@ void bmi160SpiAccInit(accDev_t *acc) acc->acc_1G = 512 * 8; } - bool bmi160SpiAccDetect(accDev_t *acc) { if (acc->mpuDetectionResult.sensor != BMI_160_SPI) { @@ -467,7 +464,6 @@ bool bmi160SpiAccDetect(accDev_t *acc) return true; } - bool bmi160SpiGyroDetect(gyroDev_t *gyro) { if (gyro->mpuDetectionResult.sensor != BMI_160_SPI) { diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c index 3eb93c29e..4156d9871 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -555,7 +555,6 @@ bool bmi270SpiAccDetect(accDev_t *acc) return true; } - bool bmi270SpiGyroDetect(gyroDev_t *gyro) { if (gyro->mpuDetectionResult.sensor != BMI_270_SPI) { diff --git a/src/main/drivers/accgyro/accgyro_spi_icm20649.c b/src/main/drivers/accgyro/accgyro_spi_icm20649.c index 4075b7bbe..bc9ce7963 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm20649.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm20649.c @@ -38,7 +38,6 @@ #include "drivers/sensor.h" #include "drivers/time.h" - // 8 MHz max SPI frequency #define ICM20649_MAX_SPI_CLK_HZ 8000000 @@ -98,7 +97,6 @@ bool icm20649SpiAccDetect(accDev_t *acc) return true; } - void icm20649GyroInit(gyroDev_t *gyro) { mpuGyroInit(gyro); diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index dcb73b4c1..1063ae4ee 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -373,7 +373,6 @@ void icm426xxGyroInit(gyroDev_t *gyro) intfConfig1Value |= ICM426XX_INTF_CONFIG1_AFSR_DISABLE; spiWriteReg(dev, ICM426XX_INTF_CONFIG1, intfConfig1Value); - // Turn on gyro and acc on again so ODR and FSR can be configured turnGyroAccOn(dev); diff --git a/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c b/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c index e058b5068..a4ae648ed 100644 --- a/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c +++ b/src/main/drivers/accgyro/accgyro_spi_lsm6dsv16x.c @@ -289,7 +289,6 @@ #define LSM6DSV_CTRL2_ODR_G_3200HZ 11 #define LSM6DSV_CTRL2_ODR_G_6400HZ 12 - // Control register 3 (R/W) #define LSM6DSV_CTRL3 0x12 #define LSM6DSV_CTRL3_BOOT 0x80 @@ -846,7 +845,6 @@ #define LSM6DSV_FIFO_DATA_OUT_Z_L 0x7D #define LSM6DSV_FIFO_DATA_OUT_Z_H 0x7E - uint8_t lsm6dsv16xSpiDetect(const extDevice_t *dev) { const uint8_t whoAmI = spiReadRegMsk(dev, LSM6DSV_WHO_AM_I); diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c index c3dc8d204..b94293758 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c @@ -44,7 +44,6 @@ #include "drivers/sensor.h" #include "drivers/system.h" - static void mpu6000AccAndGyroInit(gyroDev_t *gyro); // 20 MHz max SPI frequency diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c index c2049368d..633a614d2 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c @@ -49,7 +49,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro); - bool mpu9250SpiWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) { delayMicroseconds(1); diff --git a/src/main/drivers/accgyro/accgyro_virtual.c b/src/main/drivers/accgyro/accgyro_virtual.c index df771f682..b986aab21 100644 --- a/src/main/drivers/accgyro/accgyro_virtual.c +++ b/src/main/drivers/accgyro/accgyro_virtual.c @@ -102,7 +102,6 @@ bool virtualGyroDetect(gyroDev_t *gyro) } #endif // USE_VIRTUAL_GYRO - #ifdef USE_VIRTUAL_ACC static int16_t virtualAccData[XYZ_AXIS_COUNT]; diff --git a/src/main/drivers/accgyro/gyro_sync.c b/src/main/drivers/accgyro/gyro_sync.c index a514e2cb8..48ca30039 100644 --- a/src/main/drivers/accgyro/gyro_sync.c +++ b/src/main/drivers/accgyro/gyro_sync.c @@ -34,7 +34,6 @@ #include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/gyro_sync.h" - bool gyroSyncCheckUpdate(gyroDev_t *gyro) { bool ret; diff --git a/src/main/drivers/accgyro/legacy/accgyro_l3g4200d.c b/src/main/drivers/accgyro/legacy/accgyro_l3g4200d.c index bd02f9285..6dbcf4b96 100644 --- a/src/main/drivers/accgyro/legacy/accgyro_l3g4200d.c +++ b/src/main/drivers/accgyro/legacy/accgyro_l3g4200d.c @@ -38,7 +38,6 @@ #include "drivers/sensor.h" #include "drivers/system.h" - // L3G4200D, Standard address 0x68 #define L3G4200D_ADDRESS 0x68 #define L3G4200D_ID 0xD3 diff --git a/src/main/drivers/accgyro/legacy/accgyro_lsm303dlhc.h b/src/main/drivers/accgyro/legacy/accgyro_lsm303dlhc.h index ccf3df51d..f8024ddcf 100644 --- a/src/main/drivers/accgyro/legacy/accgyro_lsm303dlhc.h +++ b/src/main/drivers/accgyro/legacy/accgyro_lsm303dlhc.h @@ -431,5 +431,4 @@ typedef struct { #define LSM303DLHC_TEMPSENSOR_ENABLE ((uint8_t) 0x80) /*!< Temp sensor Enable */ #define LSM303DLHC_TEMPSENSOR_DISABLE ((uint8_t) 0x00) /*!< Temp sensor Disable */ - bool lsm303dlhcAccDetect(accDev_t *acc); diff --git a/src/main/drivers/barometer/barometer_2smpb_02b.c b/src/main/drivers/barometer/barometer_2smpb_02b.c index 0b9624285..0af77c4b9 100644 --- a/src/main/drivers/barometer/barometer_2smpb_02b.c +++ b/src/main/drivers/barometer/barometer_2smpb_02b.c @@ -99,7 +99,6 @@ typedef struct { static baroState_t baroState; static uint8_t baroDataBuf[6]; - static int32_t readSignedRegister(const extDevice_t *dev, uint8_t reg, uint8_t nBytes) { uint8_t buf[3]; diff --git a/src/main/drivers/barometer/barometer_bmp280.c b/src/main/drivers/barometer/barometer_bmp280.c index 359757fe0..77773888e 100644 --- a/src/main/drivers/barometer/barometer_bmp280.c +++ b/src/main/drivers/barometer/barometer_bmp280.c @@ -42,7 +42,6 @@ #if defined(USE_BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)) - #define BMP280_I2C_ADDR (0x76) #define BMP280_DEFAULT_CHIP_ID (0x58) #define BME280_DEFAULT_CHIP_ID (0x60) diff --git a/src/main/drivers/barometer/barometer_bmp388.c b/src/main/drivers/barometer/barometer_bmp388.c index 8ca06a30d..c7dfbb8dd 100644 --- a/src/main/drivers/barometer/barometer_bmp388.c +++ b/src/main/drivers/barometer/barometer_bmp388.c @@ -183,7 +183,6 @@ static bool bmp388ReadUP(baroDev_t *baro); STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature); - static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length) { if (dev->bus->busType == BUS_TYPE_SPI) { @@ -297,7 +296,6 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro) // read calibration bmp388ReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t)); - // set oversampling busWriteRegister(dev, BMP388_OSR_REG, ((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) | diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c index 39f84c199..9653f95d0 100644 --- a/src/main/drivers/barometer/barometer_dps310.c +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -314,8 +314,6 @@ static void deviceCalculate(int32_t *pressure, int32_t *temperature) } } - - #define DETECTION_MAX_RETRY_COUNT 5 static bool deviceDetect(const extDevice_t *dev) { diff --git a/src/main/drivers/barometer/barometer_ms5611.c b/src/main/drivers/barometer/barometer_ms5611.c index 0e8eb3d6a..41af52619 100644 --- a/src/main/drivers/barometer/barometer_ms5611.c +++ b/src/main/drivers/barometer/barometer_ms5611.c @@ -217,7 +217,6 @@ STATIC_UNIT_TESTED void ms5611Calculate(int32_t *pressure, int32_t *temperature) } press = ((((int64_t)ms5611_up * sens) >> 21) - off) >> 15; - if (pressure) *pressure = press; if (temperature) diff --git a/src/main/drivers/barometer/barometer_qmp6988.c b/src/main/drivers/barometer/barometer_qmp6988.c index fc1e2eec2..5887d8462 100644 --- a/src/main/drivers/barometer/barometer_qmp6988.c +++ b/src/main/drivers/barometer/barometer_qmp6988.c @@ -342,8 +342,6 @@ static float qmp6988CompensateTemperature(int32_t adc_T) return T; } - - STATIC_UNIT_TESTED void qmp6988Calculate(int32_t *pressure, int32_t *temperature) { float tr,pr; diff --git a/src/main/drivers/barometer/barometer_virtual.c b/src/main/drivers/barometer/barometer_virtual.c index b4b142e82..e5ca2564e 100644 --- a/src/main/drivers/barometer/barometer_virtual.c +++ b/src/main/drivers/barometer/barometer_virtual.c @@ -30,11 +30,9 @@ #include "barometer.h" #include "barometer_virtual.h" - static int32_t virtualPressure; static int32_t virtualTemperature; - static bool virtualBaroStart(baroDev_t *baro) { UNUSED(baro); diff --git a/src/main/drivers/bus.c b/src/main/drivers/bus.c index 031de9411..36ce3cff5 100644 --- a/src/main/drivers/bus.c +++ b/src/main/drivers/bus.c @@ -27,7 +27,6 @@ #include "drivers/bus_i2c_busdev.h" #include "drivers/bus_spi.h" - // Access routines where the register is accessed directly bool busRawWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) { @@ -77,7 +76,6 @@ bool busRawReadRegisterBufferStart(const extDevice_t *dev, uint8_t reg, uint8_t } } - // Write routines where the register is masked with 0x7f bool busWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) { diff --git a/src/main/drivers/bus_octospi.h b/src/main/drivers/bus_octospi.h index 14178bd79..34b076454 100644 --- a/src/main/drivers/bus_octospi.h +++ b/src/main/drivers/bus_octospi.h @@ -42,7 +42,6 @@ typedef enum OCTOSPIDevice { OCTOSPIDevice octoSpiDeviceByInstance(OCTOSPI_TypeDef *instance); OCTOSPI_TypeDef *octoSpiInstanceByDevice(OCTOSPIDevice device); - bool octoSpiInit(OCTOSPIDevice device); bool octoSpiReceive1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); bool octoSpiReceive4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); @@ -55,7 +54,6 @@ bool octoSpiTransmitWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruc bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize); - void octoSpiDisableMemoryMappedMode(OCTOSPI_TypeDef *instance); void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instance); diff --git a/src/main/drivers/bus_quadspi.c b/src/main/drivers/bus_quadspi.c index 1ebc4903d..4944e12d0 100644 --- a/src/main/drivers/bus_quadspi.c +++ b/src/main/drivers/bus_quadspi.c @@ -262,7 +262,6 @@ void quadSpiPinConfigure(const quadSpiConfig_t *pConfig) haveResources = haveResources && pDev->bk2CS; } - if (haveResources) { pDev->dev = hw->reg; pDev->rcc = hw->rcc; diff --git a/src/main/drivers/bus_quadspi.h b/src/main/drivers/bus_quadspi.h index fa56271df..6defb3514 100644 --- a/src/main/drivers/bus_quadspi.h +++ b/src/main/drivers/bus_quadspi.h @@ -101,7 +101,6 @@ typedef enum { // Hardware does NOT support using BK1_NCS for single flash chip on BK2. // It's possible to use BK1_NCS for single chip on BK2 using software CS via QUADSPI_BK2_CS_SOFTWARE - void quadSpiPreInit(void); bool quadSpiInit(QUADSPIDevice device); @@ -118,7 +117,6 @@ bool quadSpiReceiveWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruct bool quadSpiTransmitWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); bool quadSpiTransmitWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); - bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize); //bool quadSpiIsBusBusy(SPI_TypeDef *instance); diff --git a/src/main/drivers/bus_quadspi_impl.h b/src/main/drivers/bus_quadspi_impl.h index fb7d4d2c9..eda709b91 100644 --- a/src/main/drivers/bus_quadspi_impl.h +++ b/src/main/drivers/bus_quadspi_impl.h @@ -22,7 +22,6 @@ #pragma once - typedef struct quadSpiPinDef_s { ioTag_t pin; #if defined(STM32H7) diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 06e45967e..8badcdc0e 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -107,7 +107,6 @@ bool spiInit(SPIDevice device); // Called after all devices are initialised to enable SPI DMA where streams are available. void spiInitBusDMA(); - SPIDevice spiDeviceByInstance(const SPI_TypeDef *instance); SPI_TypeDef *spiInstanceByDevice(SPIDevice device); diff --git a/src/main/drivers/compass/compass_virtual.c b/src/main/drivers/compass/compass_virtual.c index 3beced6c2..4136b7fdb 100644 --- a/src/main/drivers/compass/compass_virtual.c +++ b/src/main/drivers/compass/compass_virtual.c @@ -33,7 +33,6 @@ #include "compass.h" #include "compass_virtual.h" - static int16_t virtualMagData[XYZ_AXIS_COUNT]; static bool virtualMagInit(magDev_t *mag) diff --git a/src/main/drivers/display_canvas.h b/src/main/drivers/display_canvas.h index e70ee1c96..9b3ba0120 100644 --- a/src/main/drivers/display_canvas.h +++ b/src/main/drivers/display_canvas.h @@ -102,7 +102,6 @@ typedef struct displayCanvasVTable_s { void (*contextPop)(displayCanvas_t *displayCanvas); } displayCanvasVTable_t; - void displayCanvasSetStrokeColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetStrokeAndFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 0fadf6ff6..ec93c09a7 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -135,7 +135,6 @@ typedef enum { #define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift) #define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift)) - #define DMA_IT_TCIF ((uint32_t)0x00000020) #define DMA_IT_HTIF ((uint32_t)0x00000010) #define DMA_IT_TEIF ((uint32_t)0x00000008) diff --git a/src/main/drivers/dshot.h b/src/main/drivers/dshot.h index 0d4b01730..40f592d83 100644 --- a/src/main/drivers/dshot.h +++ b/src/main/drivers/dshot.h @@ -100,7 +100,6 @@ typedef struct dshotTelemetryMotorState_s { uint8_t maxTemp; } dshotTelemetryMotorState_t; - typedef struct dshotTelemetryState_s { bool useDshotTelemetry; uint32_t invalidPacketCount; diff --git a/src/main/drivers/dshot_bitbang_decode.c b/src/main/drivers/dshot_bitbang_decode.c index bbb8438c6..757eb652d 100644 --- a/src/main/drivers/dshot_bitbang_decode.c +++ b/src/main/drivers/dshot_bitbang_decode.c @@ -44,7 +44,6 @@ uint16_t bbBuffer[134]; #endif - /* Bit band SRAM definitions */ #define BITBAND_SRAM_REF 0x20000000 #define BITBAND_SRAM_BASE 0x22000000 @@ -71,7 +70,6 @@ uint32_t sequence[MAX_GCR_EDGES]; int sequenceIndex = 0; #endif - static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit) { #ifndef DEBUG_BBDECODE diff --git a/src/main/drivers/dshot_dpwm.h b/src/main/drivers/dshot_dpwm.h index a9087998a..1c6a7400f 100644 --- a/src/main/drivers/dshot_dpwm.h +++ b/src/main/drivers/dshot_dpwm.h @@ -42,7 +42,6 @@ #define DSHOT_TELEMETRY_DEADTIME_US (30 + 5) // 30 to switch lines and 5 to switch lines back - typedef uint8_t loadDmaBufferFn(uint32_t *dmaBuffer, int stride, uint16_t packet); // function pointer used to encode a digital motor value into the DMA buffer representation extern FAST_DATA_ZERO_INIT loadDmaBufferFn *loadDmaBuffer; uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet); diff --git a/src/main/drivers/flash/flash.c b/src/main/drivers/flash/flash.c index a28e8a5d9..c38dfc7a9 100644 --- a/src/main/drivers/flash/flash.c +++ b/src/main/drivers/flash/flash.c @@ -226,7 +226,6 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig) quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_ULTRAFAST); - for (uint8_t offset = 0; offset <= 1 && !detected; offset++) { uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]); diff --git a/src/main/drivers/flash/flash.h b/src/main/drivers/flash/flash.h index da75304bb..964ba549c 100644 --- a/src/main/drivers/flash/flash.h +++ b/src/main/drivers/flash/flash.h @@ -48,7 +48,6 @@ typedef struct flashGeometry_s { uint32_t jedecId; } flashGeometry_t; - typedef enum { /* * When set it indicates the system was booted in memory mapped mode, flash chip is already configured by @@ -76,7 +75,6 @@ const flashGeometry_t *flashGetGeometry(void); void flashMemoryMappedModeDisable(void); void flashMemoryMappedModeEnable(void); - // // flash partitioning api // diff --git a/src/main/drivers/flash/flash_m25p16.c b/src/main/drivers/flash/flash_m25p16.c index 5abc44248..96f6aed92 100644 --- a/src/main/drivers/flash/flash_m25p16.c +++ b/src/main/drivers/flash/flash_m25p16.c @@ -274,7 +274,6 @@ void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags) } } - static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress) { if (useLongAddress) { @@ -332,7 +331,6 @@ busStatus_e m25p16_callbackReady(uint32_t arg) return BUS_READY; } - /** * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. */ @@ -411,7 +409,6 @@ static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, vo fdevice->currentWriteAddress = address; } - static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) { // The segment list cannot be in automatic storage as this routine is non-blocking @@ -566,7 +563,6 @@ static void m25p16_pageProgramQspi(flashDevice_t *fdevice, uint32_t address, con } #endif /* USE_QUADSPI */ - /** * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie * on a page boundary). diff --git a/src/main/drivers/flash/flash_w25n.c b/src/main/drivers/flash/flash_w25n.c index d88b95371..f91c87d70 100644 --- a/src/main/drivers/flash/flash_w25n.c +++ b/src/main/drivers/flash/flash_w25n.c @@ -268,7 +268,6 @@ static void w25n_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data) #endif } - static void w25n_deviceReset(flashDevice_t *fdevice) { flashDeviceIO_t *io = &fdevice->io; @@ -373,7 +372,6 @@ bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID) static void w25n_deviceInit(flashDevice_t *flashdev); - void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { @@ -1018,7 +1016,6 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg) flashDevice_t *fdevice = cb_context->fdevice; uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->u.buffers.rxData; - cb_context->bblut->pba = (rxData[0] << 16)|rxData[1]; cb_context->bblut->lba = (rxData[2] << 16)|rxData[3]; @@ -1030,7 +1027,6 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg) return BUS_READY; // All done } - void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) { cb_context_t cb_context; diff --git a/src/main/drivers/flash/flash_w25q128fv.c b/src/main/drivers/flash/flash_w25q128fv.c index 6df758b11..4205c5a8d 100644 --- a/src/main/drivers/flash/flash_w25q128fv.c +++ b/src/main/drivers/flash/flash_w25q128fv.c @@ -57,7 +57,6 @@ #define W25Q128FV_STATUS_REGISTER_BITS 8 #define W25Q128FV_ADDRESS_BITS 24 - // Instructions #define W25Q128FV_INSTRUCTION_RDID 0x9F @@ -90,7 +89,6 @@ #define W25Q128FV_SR2_BIT_QUAD_ENABLE (1 << 1) - //#define W25Q128FV_INSTRUCTION_WRITE_DISABLE 0x04 //#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02 @@ -103,7 +101,6 @@ #define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 3 // tPPmax = 3ms, tPPtyp = 0.7ms #define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 1 - typedef enum { INITIAL_MODE_SPI = 0, INITIAL_MODE_QUADSPI, @@ -168,7 +165,6 @@ MMFLASH_CODE static uint8_t w25q128fv_readRegister(flashDeviceIO_t *io, uint8_t octoSpiReceive1LINE(octoSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8); #endif - return in[0]; } @@ -204,7 +200,6 @@ static void w25q128fv_deviceReset(flashDevice_t *fdevice) w25q128fv_writeRegister(io, W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG, 0x00); #endif - #if defined(USE_FLASH_WRITES_USING_4LINES) || defined(USE_FLASH_READS_USING_4LINES) uint8_t registerValue = w25q128fv_readRegister(io, W25Q128FV_INSTRUCTION_READ_STATUS2_REG); diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index 77796b0c7..7d7d7f217 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -30,7 +30,6 @@ #include "drivers/serial.h" #include "drivers/serial_impl.h" - #include "inverter.h" static const serialPinConfig_t *pSerialPinConfig; diff --git a/src/main/drivers/io_def.h b/src/main/drivers/io_def.h index 4171124fe..6566bd34f 100644 --- a/src/main/drivers/io_def.h +++ b/src/main/drivers/io_def.h @@ -29,7 +29,6 @@ #define DEFIO_TAG_E(pinid) CONCAT(DEFIO_TAG_E__, pinid) #define DEFIO_TAG_E__NONE 0 - // return ioRec_t or NULL for given pinid // tags should be preferred, possibly removing it in future // io_impl.h must be included when this macro is used diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h index d4a1ad2fb..d67ba95be 100644 --- a/src/main/drivers/io_def_generated.h +++ b/src/main/drivers/io_def_generated.h @@ -107,8 +107,6 @@ #endif #define DEFIO_PORT_I_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) - - // DEFIO_GPIOID__ maps to port index #define DEFIO_GPIOID__A 0 #define DEFIO_GPIOID__B 1 diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index bd01af20a..bbd59e2ba 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -200,7 +200,6 @@ bool ws2811UpdateStrip(ledStripFormatRGB_e ledFormat, uint8_t brightness) return false; } - // fill transmit buffer with correct compare values to achieve // correct pulse widths according to color values const unsigned ledUpdateCount = needsFullRefresh ? WS2811_DATA_BUFFER_SIZE : usedLedCount; diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index ea528c49e..50b82151f 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -41,7 +41,6 @@ #include "drivers/osd_symbols.h" #include "drivers/time.h" - // 10 MHz max SPI frequency #define MAX7456_MAX_SPI_CLK_HZ 10000000 #define MAX7456_INIT_MAX_SPI_CLK_HZ 5000000 diff --git a/src/main/drivers/motor.h b/src/main/drivers/motor.h index f90418b06..2203ce7c2 100644 --- a/src/main/drivers/motor.h +++ b/src/main/drivers/motor.h @@ -41,7 +41,6 @@ typedef enum { PWM_TYPE_MAX } motorPwmProtocolTypes_e; - typedef struct motorVTable_s { // Common void (*postInit)(void); diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index e6db969c8..fa9efee18 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -20,7 +20,6 @@ #pragma once - // can't use 0 #define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1) #define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1) diff --git a/src/main/drivers/pin_pull_up_down.c b/src/main/drivers/pin_pull_up_down.c index 56479b687..21c331034 100644 --- a/src/main/drivers/pin_pull_up_down.c +++ b/src/main/drivers/pin_pull_up_down.c @@ -29,7 +29,6 @@ #include "pg/pin_pull_up_down.h" #include "pin_pull_up_down.h" - static void initPin(const pinPullUpDownConfig_t* config, resourceOwner_e owner, uint8_t index) { IO_t io = IOGetByTag(config->ioTag); diff --git a/src/main/drivers/pwm_output_dshot_shared.c b/src/main/drivers/pwm_output_dshot_shared.c index 9ec99858d..998112bec 100644 --- a/src/main/drivers/pwm_output_dshot_shared.c +++ b/src/main/drivers/pwm_output_dshot_shared.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include #include @@ -140,12 +139,10 @@ FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value) } - #ifdef USE_DSHOT_TELEMETRY void dshotEnableChannels(uint8_t motorCount); - static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count) { uint32_t value = 0; diff --git a/src/main/drivers/rangefinder/rangefinder_hcsr04.c b/src/main/drivers/rangefinder/rangefinder_hcsr04.c index e9dba4d93..a8192c08c 100644 --- a/src/main/drivers/rangefinder/rangefinder_hcsr04.c +++ b/src/main/drivers/rangefinder/rangefinder_hcsr04.c @@ -41,7 +41,6 @@ #define HCSR04_DETECTION_CONE_DECIDEGREES 300 // recommended cone angle30 degrees, from HC-SR04 spec sheet #define HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES 450 // in practice 45 degrees seems to work well - /* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits. * When triggered it sends out a series of 40KHz ultrasonic pulses and receives * echo from an object. The distance between the unit and the object is calculated diff --git a/src/main/drivers/rx/rx_nrf24l01.h b/src/main/drivers/rx/rx_nrf24l01.h index d315d757b..9db0ce2fc 100644 --- a/src/main/drivers/rx/rx_nrf24l01.h +++ b/src/main/drivers/rx/rx_nrf24l01.h @@ -154,7 +154,6 @@ enum { NRF24L01_04_SETUP_RETR_ARC_14 = 0x0e, NRF24L01_04_SETUP_RETR_ARC_15 = 0x0f, - NRF24L01_06_RF_SETUP_RF_DR_2Mbps = 0x08, NRF24L01_06_RF_SETUP_RF_DR_1Mbps = 0x00, NRF24L01_06_RF_SETUP_RF_DR_250Kbps = 0x20, @@ -185,7 +184,6 @@ uint8_t NRF24L01_ReadReg(uint8_t reg); void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length); void NRF24L01_ReadPayload(uint8_t *data, uint8_t length); - // Utility functions void NRF24L01_FlushTx(void); diff --git a/src/main/drivers/rx/rx_pwm.c b/src/main/drivers/rx/rx_pwm.c index fd9932b69..c42c7d3c6 100644 --- a/src/main/drivers/rx/rx_pwm.c +++ b/src/main/drivers/rx/rx_pwm.c @@ -209,7 +209,6 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture ppmDev.overflowed = false; - /* Store the current measurement */ ppmDev.currentTime = currentTime; ppmDev.currentCapture = capture; diff --git a/src/main/drivers/rx/rx_sx1280.c b/src/main/drivers/rx/rx_sx1280.c index d694e763b..38d1ff1b6 100644 --- a/src/main/drivers/rx/rx_sx1280.c +++ b/src/main/drivers/rx/rx_sx1280.c @@ -71,7 +71,6 @@ static sx1280PacketTypes_e sx1280PacketMode; #define SX1280_BUSY_TIMEOUT_US 1000 - bool sx1280IsBusy(void) { return IORead(busy); @@ -940,7 +939,6 @@ static busStatus_e sx1280EnableIRQs(uint32_t arg) return BUS_READY; } - // Send telemetry response static void sx1280SendTelemetryBuffer(extiCallbackRec_t *cb) { diff --git a/src/main/drivers/rx/rx_xn297.c b/src/main/drivers/rx/rx_xn297.c index a925d7668..e390360ff 100644 --- a/src/main/drivers/rx/rx_xn297.c +++ b/src/main/drivers/rx/rx_xn297.c @@ -35,7 +35,6 @@ #include "drivers/rx/rx_nrf24l01.h" #include "drivers/rx/rx_spi.h" - static const uint8_t xn297_data_scramble[30] = { 0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12, 0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b, @@ -60,7 +59,6 @@ static uint8_t bitReverse(uint8_t bIn) return bOut; } - #define RX_TX_ADDR_LEN 5 uint16_t XN297_UnscramblePayload(uint8_t *data, int len, const uint8_t *rxAddr) diff --git a/src/main/drivers/sdcard_spi.c b/src/main/drivers/sdcard_spi.c index 5f765ceb8..c23ded450 100644 --- a/src/main/drivers/sdcard_spi.c +++ b/src/main/drivers/sdcard_spi.c @@ -110,7 +110,6 @@ static void sdcard_reset(void) } } - // Called in ISR context // Wait until idle indicated by a read value of 0xff busStatus_e sdcard_callbackIdle(uint32_t arg) @@ -132,7 +131,6 @@ busStatus_e sdcard_callbackIdle(uint32_t arg) return BUS_BUSY; } - // Called in ISR context // Wait until idle is no longer indicated by a read value of 0xff busStatus_e sdcard_callbackNotIdle(uint32_t arg) @@ -153,7 +151,6 @@ busStatus_e sdcard_callbackNotIdle(uint32_t arg) return BUS_BUSY; } - /** * The SD card spec requires 8 clock cycles to be sent by us on the bus after most commands so it can finish its * processing of that command. The easiest way for us to do this is to just wait for the bus to become idle before diff --git a/src/main/drivers/sdmmc_sdio.h b/src/main/drivers/sdmmc_sdio.h index 647cb2d73..683a6b1b7 100644 --- a/src/main/drivers/sdmmc_sdio.h +++ b/src/main/drivers/sdmmc_sdio.h @@ -109,7 +109,6 @@ typedef enum SD_SDMMC_UNKNOWN_FUNCTION = (33), SD_OUT_OF_BOUND = (34), - // Standard error defines SD_INTERNAL_ERROR = (35), SD_NOT_CONFIGURED = (36), @@ -123,7 +122,6 @@ typedef enum SD_OK = (0) } SD_Error_t; - typedef struct { uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index d93bddb77..ea772a6cb 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -44,7 +44,6 @@ void serialWrite(serialPort_t *instance, uint8_t ch) instance->vTable->serialWrite(instance, ch); } - void serialWriteBufNoFlush(serialPort_t *instance, const uint8_t *data, int count) { if (instance->vTable->writeBuf) { diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 072560a50..369851d05 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -46,7 +46,6 @@ #include "pg/motor.h" - typedef enum { BAUDRATE_NORMAL = 19200, BAUDRATE_SIMONK = 28800, // = 9600 * 3 @@ -238,7 +237,6 @@ static void processTxStateBL(escSerial_t *escSerial) escSerial->bitsLeftToTransmit = TX_TOTAL_BITS; escSerial->isTransmittingData = true; - //set output if (escSerial->mode==PROTOCOL_BLHELI || escSerial->mode==PROTOCOL_CASTLE) { escSerialOutputPortConfig(escSerial->rxTimerHardware); @@ -468,7 +466,6 @@ reload: } } - // build internal buffer, data bits (MSB to LSB) escSerial->internalTxBuffer = byteToSend; escSerial->bitsLeftToTransmit = 8; @@ -661,7 +658,6 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria { escSerial_t *escSerial = &(escSerialPorts[portIndex]); - if (mode != PROTOCOL_KISSALL) { if (escSerialConfig()->ioTag == IO_TAG_NONE) { @@ -780,7 +776,6 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria return &escSerial->port; } - static void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr) { timerChClearCCFlag(timerHardwarePtr); @@ -788,7 +783,6 @@ static void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr) escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU); } - static void closeEscSerial(escSerialPortIndex_e portIndex, uint8_t mode) { escSerial_t *escSerial = &(escSerialPorts[portIndex]); @@ -951,7 +945,6 @@ static bool processExitCommand(uint8_t c) return false; } - bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig_t *motorConfig, uint16_t escIndex, uint8_t mode) { bool exitEsc = false; diff --git a/src/main/drivers/serial_impl.c b/src/main/drivers/serial_impl.c index fbca45044..5ef5664e3 100644 --- a/src/main/drivers/serial_impl.c +++ b/src/main/drivers/serial_impl.c @@ -3,7 +3,6 @@ #include "platform.h" - #include "io/serial.h" #include "serial.h" @@ -36,4 +35,3 @@ bool serialOptions_pushPull(portOptions_e options) return options & (SERIAL_INVERTED | SERIAL_BIDIR_PP); } - diff --git a/src/main/drivers/serial_impl.h b/src/main/drivers/serial_impl.h index 7f2e0068a..029eed414 100644 --- a/src/main/drivers/serial_impl.h +++ b/src/main/drivers/serial_impl.h @@ -36,4 +36,3 @@ typedef enum { serialPullNone = 0, serialPullDown = 1, serialPullUp = 2 } serial serialPullMode_t serialOptions_pull(portOptions_e options); bool serialOptions_pushPull(portOptions_e options); - diff --git a/src/main/drivers/serial_pinconfig.c b/src/main/drivers/serial_pinconfig.c index 7c9eb870f..71a1bf57e 100644 --- a/src/main/drivers/serial_pinconfig.c +++ b/src/main/drivers/serial_pinconfig.c @@ -100,5 +100,4 @@ void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig) } } - #endif diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index f3fd39c97..010c1ee1e 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -326,7 +326,6 @@ serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCal return &softSerial->port; } - /* * Serial Engine */ @@ -534,7 +533,6 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) #endif } - /* * Standard serial driver API */ diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index c27861385..42c784693 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -606,5 +606,4 @@ UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler #endif - #endif // USE_UART diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 3b97b6ed3..0b6b5739f 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -32,7 +32,6 @@ #include "drivers/resource.h" #include "drivers/sound_beeper.h" - #include "system.h" #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) || defined(APM32F4) diff --git a/src/main/drivers/transponder_ir.h b/src/main/drivers/transponder_ir.h index 94298aa7e..a4f8a44f3 100644 --- a/src/main/drivers/transponder_ir.h +++ b/src/main/drivers/transponder_ir.h @@ -35,7 +35,6 @@ #define TRANSPONDER_TRANSMIT_JITTER_ARCITIMER 10000 /*** ******** ***/ - /*** ILAP ***/ #define TRANSPONDER_BITS_PER_BYTE_ILAP 10 // start + 8 data + stop #define TRANSPONDER_DATA_LENGTH_ILAP 6 @@ -49,7 +48,6 @@ #define TRANSPONDER_TRANSMIT_JITTER_ILAP 10000 /*** ******** ***/ - /*** ERLT ***/ #define TRANSPONDER_DATA_LENGTH_ERLT 1 @@ -63,7 +61,6 @@ #define TRANSPONDER_TRANSMIT_JITTER_ERLT 5000 /*** ******** ***/ - /* * Implementation note: * Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast diff --git a/src/main/drivers/transponder_ir_arcitimer.c b/src/main/drivers/transponder_ir_arcitimer.c index 68f34e231..4229af979 100644 --- a/src/main/drivers/transponder_ir_arcitimer.c +++ b/src/main/drivers/transponder_ir_arcitimer.c @@ -66,8 +66,6 @@ void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8 dmaBufferOffset = 0; } - - const struct transponderVTable arcitimerTansponderVTable = { updateTransponderDMABufferArcitimer, }; diff --git a/src/main/drivers/transponder_ir_arcitimer.h b/src/main/drivers/transponder_ir_arcitimer.h index e17195b0a..0bf8f7224 100644 --- a/src/main/drivers/transponder_ir_arcitimer.h +++ b/src/main/drivers/transponder_ir_arcitimer.h @@ -34,7 +34,5 @@ // ID8 0xFF, 0x3, 0xF0, 0x1, 0xF8, 0xE0, 0xC1, 0xFF, 0x1 // 00FC0FFE071F3E00FE // ID9 0x1F, 0x7C, 0x40, 0xF, 0xF0, 0x61, 0xC7, 0x3F, 0x0 // E083BFF00F9E38C0FF - - void transponderIrInitArcitimer(transponder_t *transponder); void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData); diff --git a/src/main/drivers/vtx_common.c b/src/main/drivers/vtx_common.c index 64821a73d..245bbc329 100644 --- a/src/main/drivers/vtx_common.c +++ b/src/main/drivers/vtx_common.c @@ -33,7 +33,6 @@ #include "drivers/vtx_common.h" #include "drivers/vtx_table.h" - static vtxDevice_t *vtxDevice = NULL; static uint8_t selectedBand = 0; static uint8_t selectedChannel = 0; diff --git a/src/main/drivers/vtx_common.h b/src/main/drivers/vtx_common.h index 4897fe0ef..bbb80475e 100644 --- a/src/main/drivers/vtx_common.h +++ b/src/main/drivers/vtx_common.h @@ -95,7 +95,6 @@ typedef struct vtxDevice_s { const struct vtxVTable_s *const vTable; } vtxDevice_t; - // {set,get}BandAndChannel: band and channel are 1 origin // {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent // {set,get}PitMode: 0 = OFF, 1 = ON diff --git a/src/main/drivers/vtx_rtc6705.h b/src/main/drivers/vtx_rtc6705.h index 0395386c6..bc56c0352 100644 --- a/src/main/drivers/vtx_rtc6705.h +++ b/src/main/drivers/vtx_rtc6705.h @@ -44,4 +44,3 @@ void rtc6705SetRFPower(uint8_t rf_power); void rtc6705Disable(void); void rtc6705Enable(void); - diff --git a/src/main/drivers/vtx_rtc6705_soft_spi.c b/src/main/drivers/vtx_rtc6705_soft_spi.c index 09e29be90..6adc3606f 100644 --- a/src/main/drivers/vtx_rtc6705_soft_spi.c +++ b/src/main/drivers/vtx_rtc6705_soft_spi.c @@ -31,7 +31,6 @@ #include "drivers/time.h" #include "drivers/vtx_rtc6705.h" - #define DP_5G_MASK 0x7000 #define PA5G_BS_MASK 0x0E00 #define PA5G_PW_MASK 0x0180 @@ -54,7 +53,6 @@ static IO_t rtc6705DataPin = IO_NONE; static IO_t rtc6705CsnPin = IO_NONE; static IO_t rtc6705ClkPin = IO_NONE; - bool rtc6705SoftSpiIOInit(const vtxIOConfig_t *vtxIOConfig, const IO_t csnPin) { rtc6705CsnPin = csnPin; diff --git a/src/main/drivers/vtx_rtc6705_soft_spi.h b/src/main/drivers/vtx_rtc6705_soft_spi.h index ce88c5815..3fb38ada8 100644 --- a/src/main/drivers/vtx_rtc6705_soft_spi.h +++ b/src/main/drivers/vtx_rtc6705_soft_spi.h @@ -28,4 +28,3 @@ bool rtc6705SoftSpiIOInit(const vtxIOConfig_t *vtxIOConfig, const IO_t csnPin); void rtc6705SoftSpiSetFrequency(uint16_t freq); void rtc6705SoftSpiSetRFPower(uint8_t rf_power); - diff --git a/src/main/drivers/vtx_table.c b/src/main/drivers/vtx_table.c index 1d678e10f..5e29e5a54 100644 --- a/src/main/drivers/vtx_table.c +++ b/src/main/drivers/vtx_table.c @@ -36,7 +36,6 @@ #include "drivers/vtx_common.h" #endif - #if defined(USE_VTX_TABLE) int vtxTableBandCount; int vtxTableChannelCount; diff --git a/src/main/drivers/vtx_table.h b/src/main/drivers/vtx_table.h index 0783f8ab2..be3dafec8 100644 --- a/src/main/drivers/vtx_table.h +++ b/src/main/drivers/vtx_table.h @@ -42,7 +42,6 @@ #define VTX_TABLE_POWER_LABEL_LENGTH 3 #endif - #define VTX_TABLE_MIN_USER_FREQ 5000 #define VTX_TABLE_MAX_USER_FREQ 5999 #define VTX_TABLE_DEFAULT_BAND 4 diff --git a/src/main/fc/core.c b/src/main/fc/core.c index 4548d5d4f..f73f7e2de 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -108,7 +108,6 @@ #include "core.h" - enum { ALIGN_GYRO = 0, ALIGN_ACCEL = 1, @@ -735,7 +734,6 @@ void runawayTakeoffTemporaryDisable(uint8_t disableFlag) } #endif - // calculate the throttle stick percent - integer math is good enough here. // returns negative values for reversed thrust in 3D mode int8_t calculateThrottlePercent(void) @@ -1195,7 +1193,6 @@ static FAST_CODE_NOINLINE void subTaskPidController(timeUs_t currentTimeUs) } #endif - #ifdef USE_PID_AUDIO if (isModeActivationConditionPresent(BOXPIDAUDIO)) { pidAudioUpdate(); diff --git a/src/main/fc/init.c b/src/main/fc/init.c index e5406da28..1011a8176 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -385,7 +385,6 @@ void init(void) #endif // CONFIG_IN_EXTERNAL_FLASH || CONFIG_IN_MEMORY_MAPPED_FLASH - initEEPROM(); ensureEEPROMStructureIsValid(); @@ -575,7 +574,6 @@ void init(void) initInverters(serialPinConfig()); #endif - #ifdef TARGET_BUS_INIT targetBusInit(); diff --git a/src/main/flight/dyn_notch_filter.c b/src/main/flight/dyn_notch_filter.c index 695a5a729..e65fce94b 100644 --- a/src/main/flight/dyn_notch_filter.c +++ b/src/main/flight/dyn_notch_filter.c @@ -153,7 +153,6 @@ static FAST_DATA_ZERO_INIT int sdftEndBin; static FAST_DATA_ZERO_INIT float sdftNoiseThreshold; static FAST_DATA_ZERO_INIT float pt1LooptimeS; - void dynNotchInit(const dynNotchConfig_t *config, const timeUs_t targetLooptimeUs) { // dynNotchUpdate() is running at looprateHz (which is the PID looprate aka. 1e6f / gyro.targetLooptime) diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 2c46cb051..a4858ec38 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -399,7 +399,6 @@ static float imuCalcGroundspeedGain(float dt) // groundspeedGain is the primary multiplier of ez_ef // Otherwise, groundspeedGain is determined by GPS COG groundspeed / GPS_COG_MIN_GROUNDSPEED - // in normal flight, IMU should: // - heavily average GPS heading values at low speed, since they are random, almost // - respond more quickly at higher speeds. @@ -673,7 +672,6 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs) UNUSED(useMag); #endif - float gyroAverage[XYZ_AXIS_COUNT]; for (int axis = 0; axis < XYZ_AXIS_COUNT; ++axis) { gyroAverage[axis] = gyroGetFilteredDownsampled(axis); diff --git a/src/main/flight/mixer_init.c b/src/main/flight/mixer_init.c index 642fc73f8..b3124be59 100644 --- a/src/main/flight/mixer_init.c +++ b/src/main/flight/mixer_init.c @@ -109,7 +109,6 @@ static const motorMixer_t mixerY4[] = { { 1.0f, 1.0f, -1.0f, 0.0f }, // FRONT_L CW }; - #if (MAX_SUPPORTED_MOTORS >= 6) static const motorMixer_t mixerHex6X[] = { { 1.0f, -0.5f, 0.866025f, 1.0f }, // REAR_R diff --git a/src/main/flight/mixer_tricopter.c b/src/main/flight/mixer_tricopter.c index f50da5e9a..b6bd7f221 100644 --- a/src/main/flight/mixer_tricopter.c +++ b/src/main/flight/mixer_tricopter.c @@ -33,7 +33,6 @@ #include "pg/pg.h" #include "pg/pg_ids.h" - PG_REGISTER_WITH_RESET_TEMPLATE(tricopterMixerConfig_t, tricopterMixerConfig, PG_TRICOPTER_CONFIG, 0); PG_RESET_TEMPLATE(tricopterMixerConfig_t, tricopterMixerConfig, diff --git a/src/main/flight/mixer_tricopter.h b/src/main/flight/mixer_tricopter.h index 532b1c002..28911fb52 100644 --- a/src/main/flight/mixer_tricopter.h +++ b/src/main/flight/mixer_tricopter.h @@ -30,7 +30,6 @@ typedef struct tricopterMixerConfig_s { PG_DECLARE(tricopterMixerConfig_t, tricopterMixerConfig); - bool mixerTricopterIsServoSaturated(float errorRate); void mixerTricopterInit(void); float mixerTricopterMotorCorrection(int motor); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 80b74dd6d..8c6ada490 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -267,7 +267,6 @@ void pgResetFn_pidProfiles(pidProfile_t *pidProfiles) #define D_LPF_RAW_SCALE 25 #define D_LPF_PRE_TPA_SCALE 10 - void pidSetItermAccelerator(float newItermAccelerator) { pidRuntime.itermAccelerator = newItermAccelerator; diff --git a/src/main/flight/pid_init.c b/src/main/flight/pid_init.c index fd3226595..d6596300c 100644 --- a/src/main/flight/pid_init.c +++ b/src/main/flight/pid_init.c @@ -325,7 +325,6 @@ void pidInitFilters(const pidProfile_t *pidProfile) #endif } - #ifdef USE_ADVANCED_TPA float tpaCurveHyperbolicFunction(float x, void *args) { diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c index 2ab9012ec..feb71ec1b 100644 --- a/src/main/flight/rpm_filter.c +++ b/src/main/flight/rpm_filter.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include "platform.h" @@ -45,7 +44,6 @@ #define RPM_FILTER_DURATION_S 0.001f // Maximum duration allowed to update all RPM notches once - typedef struct rpmFilter_s { int numHarmonics; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index fd674d962..bbc3b22c8 100644 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -55,7 +55,6 @@ #include "rx/rx.h" - PG_REGISTER_WITH_RESET_FN(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0); void pgResetFn_servoConfig(servoConfig_t *servoConfig) @@ -106,7 +105,6 @@ static uint8_t servoRuleCount = 0; static servoMixer_t currentServoMixer[MAX_SERVO_RULES]; static int useServo; - #define COUNT_SERVO_RULES(rules) (sizeof(rules) / sizeof(servoMixer_t)) // mixer rule format servo, input, rate, speed, min, max, box static const servoMixer_t servoMixerAirplane[] = { @@ -264,7 +262,6 @@ static void servoConfigureOutput(void) } } - void servosInit(void) { // enable servos for mixes that require them. note, this shifts motor counts. @@ -485,7 +482,6 @@ void servoMixer(void) } } - static void servoTable(void) { // airplane / servo mixes diff --git a/src/main/flight/servos_tricopter.c b/src/main/flight/servos_tricopter.c index 740114183..a136d8bef 100644 --- a/src/main/flight/servos_tricopter.c +++ b/src/main/flight/servos_tricopter.c @@ -29,7 +29,6 @@ #include "flight/mixer_tricopter.h" #include "flight/servos.h" - bool servosTricopterIsEnabledServoUnarmed(void) { return servoConfig()->tri_unarmed_servo; diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 89a5b3413..1445c83ec 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -239,7 +239,6 @@ static const beeperTableEntry_t beeperTable[] = { static const beeperTableEntry_t *currentBeeperEntry = NULL; - // find entry by mode static const beeperTableEntry_t *beeperFind(beeperMode_e mode) { @@ -295,7 +294,6 @@ void beeperSilence(void) beeperNextToggleTime = 0; } - // helper function, add count beeps starting at pos to beep_multiBeeps // `off` is used as interval between beeps // if offLast is nonzero, it is used after sequence @@ -409,7 +407,6 @@ static enum beeperState_e beeperSequenceAdvance(timeUs_t currentTimeUs) } } - /* * Beeper handler function to be called periodically in loop. Updates beeper * state via time schedule. diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c index 80cbe69cb..a76d85800 100644 --- a/src/main/io/dashboard.c +++ b/src/main/io/dashboard.c @@ -189,7 +189,6 @@ static void fillScreenWithCharacters(void) } #endif - static void updateTicker(void) { static uint8_t tickerIndex = 0; @@ -397,7 +396,6 @@ static void showGpsPage(void) i2c_OLED_send_char(dev, VERTICAL_BARGRAPH_ZERO_CHARACTER + bargraphOffset); } - char fixChar = STATE(GPS_FIX) ? 'Y' : 'N'; tfp_sprintf(lineBuffer, "Sats: %d Fix: %c", gpsSol.numSat, fixChar); padLineBuffer(); @@ -610,7 +608,6 @@ static void showDebugPage(void) } #endif - static const pageEntry_t pages[PAGE_COUNT] = { { PAGE_WELCOME, FC_FIRMWARE_NAME, showWelcomePage, PAGE_FLAGS_SKIP_CYCLING }, { PAGE_ARMED, "ARMED", showArmedPage, PAGE_FLAGS_SKIP_CYCLING }, @@ -631,7 +628,6 @@ static const pageEntry_t pages[PAGE_COUNT] = { #endif }; - void dashboardSetPage(pageId_e pageId) { for (int i = 0; i < PAGE_COUNT; i++) { diff --git a/src/main/io/displayport_crsf.c b/src/main/io/displayport_crsf.c index 68a49ee5c..7ea2a9ef6 100644 --- a/src/main/io/displayport_crsf.c +++ b/src/main/io/displayport_crsf.c @@ -77,7 +77,6 @@ static int crsfScreenSize(const displayPort_t *displayPort) return displayPort->rows * displayPort->cols; } - static int crsfWriteString(displayPort_t *displayPort, uint8_t col, uint8_t row, uint8_t attr, const char *s) { UNUSED(displayPort); diff --git a/src/main/io/displayport_frsky_osd.c b/src/main/io/displayport_frsky_osd.c index 12eeebb5e..84c45f000 100644 --- a/src/main/io/displayport_frsky_osd.c +++ b/src/main/io/displayport_frsky_osd.c @@ -423,7 +423,6 @@ static void contextPop(displayCanvas_t *displayCanvas) frskyOsdContextPop(); } - static const displayCanvasVTable_t frskyOsdCanvasVTable = { .setStrokeColor = setStrokeColor, .setFillColor = setFillColor, diff --git a/src/main/io/displayport_srxl.c b/src/main/io/displayport_srxl.c index d12767d47..8ff10b656 100644 --- a/src/main/io/displayport_srxl.c +++ b/src/main/io/displayport_srxl.c @@ -57,7 +57,6 @@ static int srxlWriteChar(displayPort_t *displayPort, uint8_t col, uint8_t row, u return (spektrumTmTextGenPutChar(col, row, c)); } - static int srxlWriteString(displayPort_t *displayPort, uint8_t col, uint8_t row, uint8_t attr, const char *s) { while (*s) { diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 6afac961f..1c84fef9c 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -86,7 +86,6 @@ static volatile bool dataWritten = true; // The position of the buffer's tail in the overall flash address space: static uint32_t tailAddress = 0; - #ifdef USE_FLASH_TEST_PRBS // Write an incrementing sequence of bytes instead of the requested data and verify static DMA_DATA uint8_t checkFlashBuffer[FLASHFS_WRITE_BUFFER_SIZE]; @@ -360,13 +359,11 @@ static int flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferS return 0; } - static bool flashfsNewData(void) { return dataWritten; } - /** * Get the current offset of the file pointer within the volume. */ diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index 0ff6890fe..128a5c451 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -211,7 +211,6 @@ typedef struct frskyOsdDrawStrMaskCommandHeaderCmd_s { // uvarint with size and blob follow } __attribute__((packed)) frskyOsdDrawStrMaskCommandHeaderCmd_t; - typedef struct frskyOsdState_s { struct { uint8_t data[FRSKY_OSD_SEND_BUFFER_SIZE]; @@ -923,5 +922,4 @@ void frskyOsdContextPop(void) frskyOsdSendAsyncCommand(OSD_CMD_CONTEXT_POP, NULL, 0); } - #endif diff --git a/src/main/io/gimbal_control.c b/src/main/io/gimbal_control.c index 1c618c7f6..73a89f3c5 100644 --- a/src/main/io/gimbal_control.c +++ b/src/main/io/gimbal_control.c @@ -195,7 +195,6 @@ static bool gimbalSet(int16_t headtracker_roll, int16_t headtracker_pitch, int16 GIMBAL_YAW_MIN * gimbalTrackConfig()->gimbal_yaw_gain / 100, GIMBAL_YAW_MAX * gimbalTrackConfig()->gimbal_yaw_gain / 100); - // Scale the RC stick inputs and add roll += scaleRange(rcData[ROLL] - rxConfig()->midrc, GIMBAL_RC_SET_MIN, GIMBAL_RC_SET_MAX, GIMBAL_ROLL_MIN * gimbalTrackConfig()->gimbal_roll_rc_gain / 100, diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 97eec6ad0..ed2af9ec1 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -1541,7 +1541,6 @@ bool gpsIsHealthy(void) #define FRAME_GSV 3 #define FRAME_GSA 4 - // This code is used for parsing NMEA data /* Alex optimization diff --git a/src/main/io/gps.h b/src/main/io/gps.h index c22bb47fe..7aa613b9f 100644 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -351,7 +351,6 @@ extern GPS_svinfo_t GPS_svinfo[GPS_SV_MAXSATS_M8N]; #define TASK_GPS_RATE 100 // default update rate of GPS task #define TASK_GPS_RATE_FAST 500 // update rate of GPS task while Rx buffer is not empty - #ifdef USE_DASHBOARD // Data used *only* by the dashboard device (OLED display). // Note this data should probably be in the dashboard module, not here. On the refactor list... diff --git a/src/main/io/rcdevice.c b/src/main/io/rcdevice.c index 793d5c797..d5e4266ed 100644 --- a/src/main/io/rcdevice.c +++ b/src/main/io/rcdevice.c @@ -48,7 +48,6 @@ typedef enum { RCDEVICE_STATE_WAITING_CRC, } RCDEVICE_PARSER_STATE; - typedef struct { uint8_t state; uint8_t expectedDataLength; diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index a31d81175..a5e7a6ae3 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -46,7 +46,6 @@ #define IS_LO(X) (rcData[X] < FIVE_KEY_CABLE_JOYSTICK_MIN) #define IS_MID(X) (rcData[X] > FIVE_KEY_CABLE_JOYSTICK_MID_START && rcData[X] < FIVE_KEY_CABLE_JOYSTICK_MID_END) - static runcamDevice_t runcamDevice; runcamDevice_t *camDevice = &runcamDevice; rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1]; @@ -54,7 +53,6 @@ bool rcdeviceInMenu = false; bool isButtonPressed = false; bool waitingDeviceResponse = false; - static bool isFeatureSupported(uint16_t feature) { if (camDevice->info.features & feature || rcdeviceConfig()->feature & feature) { diff --git a/src/main/io/serial.c b/src/main/io/serial.c index ce8826714..325d6ec15 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -309,14 +309,12 @@ serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(con return SERIAL_PORT_NONE; } - const char* serialName(serialPortIdentifier_e identifier, const char* notFound) { const int idx = findSerialPortIndexByIdentifier(identifier); return idx >= 0 ? serialPortNames[idx] : notFound; } - serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier) { for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) { diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index bacbd9a53..6482febc2 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -173,7 +173,6 @@ void esc4wayRelease(void) motorEnable(); } - #define SET_DISCONNECTED DeviceInfo.words[0] = 0 #define INTF_MODE_IDX 3 // index for DeviceInfostate @@ -205,7 +204,6 @@ void esc4wayRelease(void) #define cmd_InterfaceGetVersion 0x33 // '3' version // RETURN: uint8_t AVersionNumber + ACK - // Exit / Restart Interface - can be used to switch to Box Mode #define cmd_InterfaceExit 0x34 // '4' exit // RETURN: ACK @@ -274,7 +272,6 @@ void esc4wayRelease(void) //PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255] //RETURN: ACK - // responses #define ACK_OK 0x00 // #define ACK_I_UNKNOWN_ERROR 0x01 @@ -336,13 +333,11 @@ uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) } // * End copyright - #define ATMEL_DEVICE_MATCH ((pDeviceInfo->words[0] == 0x9307) || (pDeviceInfo->words[0] == 0x930A) || \ (pDeviceInfo->words[0] == 0x930F) || (pDeviceInfo->words[0] == 0x940B)) #define SILABS_DEVICE_MATCH ((pDeviceInfo->words[0] > 0xE800) && (pDeviceInfo->words[0] < 0xF900)) - // BLHeli_32 MCU ID hi > 0x00 and < 0x90 / lo always = 0x06 #define ARM_DEVICE_MATCH ((pDeviceInfo->bytes[1] > 0x00) && (pDeviceInfo->bytes[1] < 0x90) && (pDeviceInfo->bytes[0] == 0x06)) @@ -511,7 +506,6 @@ void esc4wayProcess(serialPort_t *mspPort) // wtf.D_FLASH_ADDR_L=Adress_L; ioMem.D_PTR_I = ParamBuf; - switch (CMD) { // ******* Interface related stuff ******* case cmd_InterfaceTestAlive: @@ -942,6 +936,4 @@ void esc4wayProcess(serialPort_t *mspPort) } - - #endif diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c index 3cadd514c..d58e0ef68 100644 --- a/src/main/io/serial_4way_stk500v2.c +++ b/src/main/io/serial_4way_stk500v2.c @@ -40,7 +40,6 @@ #include "io/serial_4way_impl.h" #include "io/serial_4way_stk500v2.h" - #define BIT_LO_US (32) //32uS #define BIT_HI_US (2*BIT_LO_US) @@ -134,8 +133,6 @@ static void StkSendPacketFooter(void) IRQ_ON; } - - static int8_t ReadBit(void) { uint32_t btimer = micros(); @@ -397,7 +394,6 @@ uint8_t Stk_ReadFlash(ioMem_t *pMem) return 0; } - uint8_t Stk_ReadEEprom(ioMem_t *pMem) { if (_CMD_LOAD_ADDRESS(pMem)) { diff --git a/src/main/io/serial_resource.c b/src/main/io/serial_resource.c index 571cb92b8..33eb938bb 100644 --- a/src/main/io/serial_resource.c +++ b/src/main/io/serial_resource.c @@ -66,7 +66,6 @@ serialType_e serialType(serialPortIdentifier_e identifier) return SERIALTYPE_INVALID; } - static const struct SerialTypeInfo { resourceOwner_e owner; serialPortIdentifier_e firstId; @@ -99,7 +98,6 @@ resourceOwner_e serialOwnerTxRx(serialPortIdentifier_e identifier) return inf ? inf->owner : OWNER_FREE; } - // return index used to claim given resource. Returned value is 1 based, for IOInit and similar // 0 is returned when given port is not defined or if it is singleton port (USB) int serialOwnerIndex(serialPortIdentifier_e identifier) diff --git a/src/main/io/spektrum_rssi.h b/src/main/io/spektrum_rssi.h index 0ee90eb9b..f21ba7484 100644 --- a/src/main/io/spektrum_rssi.h +++ b/src/main/io/spektrum_rssi.h @@ -34,5 +34,4 @@ typedef struct dbm_table_s uint8_t reportAs; } dbm_table_t; - void spektrumHandleRSSI(volatile uint8_t spekFrame[]); diff --git a/src/main/io/spektrum_vtx_control.c b/src/main/io/spektrum_vtx_control.c index 205768c5f..910fcf525 100644 --- a/src/main/io/spektrum_vtx_control.c +++ b/src/main/io/spektrum_vtx_control.c @@ -147,7 +147,6 @@ void spektrumHandleVtxControl(uint32_t vtxCntrl) } // ########################################### - // ############ VTX_CONTROL task ############# void spektrumVtxControl(void) { diff --git a/src/main/io/spektrum_vtx_control.h b/src/main/io/spektrum_vtx_control.h index 039dad132..a6594465a 100644 --- a/src/main/io/spektrum_vtx_control.h +++ b/src/main/io/spektrum_vtx_control.h @@ -90,7 +90,6 @@ typedef struct uint16_t powerValue; } spektrumVtx_t; - extern const uint16_t SpektrumVtxfrequencyTable[SPEKTRUM_VTX_BAND_COUNT][SPEKTRUM_VTX_CHAN_COUNT]; extern const uint8_t spek2commonBand[SPEKTRUM_VTX_BAND_COUNT]; extern const uint8_t vtxTrampPi[SPEKTRUM_VTX_POWER_COUNT]; @@ -101,5 +100,3 @@ extern uint8_t SpektrumRegion; void spektrumHandleVtxControl(uint32_t vtxControl); void spektrumVtxControl(void); - - diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c index 0af76b6b9..6e9c189e8 100644 --- a/src/main/io/usb_cdc_hid.c +++ b/src/main/io/usb_cdc_hid.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include "platform.h" diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 49acc0e39..57fb0d18a 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -46,7 +46,6 @@ #include "vtx.h" - PG_REGISTER_WITH_RESET_FN(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 1); void pgResetFn_vtxSettingsConfig(vtxSettingsConfig_t *vtxSettingsConfig) diff --git a/src/main/io/vtx_control.c b/src/main/io/vtx_control.c index 8f7b74d1e..45a63d672 100644 --- a/src/main/io/vtx_control.c +++ b/src/main/io/vtx_control.c @@ -47,7 +47,6 @@ #include "pg/pg.h" #include "pg/pg_ids.h" - PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 1); PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig, @@ -57,7 +56,6 @@ PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig, static uint8_t locked = 0; - void vtxControlInit(void) { // NOTHING TO DO diff --git a/src/main/io/vtx_rtc6705.c b/src/main/io/vtx_rtc6705.c index 9789d4c7a..8c3ad7333 100644 --- a/src/main/io/vtx_rtc6705.c +++ b/src/main/io/vtx_rtc6705.c @@ -40,7 +40,6 @@ #include "io/vtx.h" #include "io/vtx_rtc6705.h" - #if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE) const char *rtc6705PowerNames[VTX_RTC6705_POWER_COUNT + 1] = { "---", "MIN", "MAX" diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 77594de30..6e9d3ea36 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -48,7 +48,6 @@ #include "io/vtx_control.h" #include "io/vtx_smartaudio.h" - // Timing parameters // Note that vtxSAProcess() is normally called at 200ms interval #define SMARTAUDIO_CMD_TIMEOUT 120 // Time until the command is considered lost @@ -85,18 +84,15 @@ enum { // This is not a good design; can't distinguish command from response this way. #define SACMD(cmd) (((cmd) << 1) | 1) - #define SA_IS_PITMODE(n) ((n) & SA_MODE_GET_PITMODE) #define SA_IS_PIRMODE(n) (((n) & SA_MODE_GET_PITMODE) && ((n) & SA_MODE_GET_IN_RANGE_PITMODE)) #define SA_IS_PORMODE(n) (((n) & SA_MODE_GET_PITMODE) && ((n) & SA_MODE_GET_OUT_RANGE_PITMODE)) - // convert between 'saDevice.channel' and band/channel values #define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)vtxTableChannelCount) + 1 #define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)vtxTableChannelCount) + 1 #define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band - 1) * (uint8_t)vtxTableChannelCount + (channel - 1)) - // Statistical counters, for user side trouble shooting. smartAudioStat_t saStat = { @@ -172,7 +168,6 @@ static uint8_t CRC8(const uint8_t *data, const int8_t len) return crc; } - #ifdef USE_SMARTAUDIO_DPRINTF static void saPrintSettings(void) { @@ -695,7 +690,6 @@ void saSetMode(int mode) saQueueCmd(buf, 6); } - bool vtxSmartAudioInit(void) { #if !defined(USE_VTX_TABLE) @@ -733,8 +727,6 @@ bool vtxSmartAudioInit(void) dprintf(("vtxSmartAudioInit %d power levels recorded\r\n", vtxTablePowerLevels)); - - vtxCommonSetDevice(&vtxSmartAudio); #ifndef USE_VTX_TABLE vtxTableSetFactoryBands(true); @@ -971,7 +963,6 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff) (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE) ? "on" : "off", (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) ? "on" : "off" , newMode)); - saSetMode(newMode); return; @@ -1092,5 +1083,4 @@ static const vtxVTable_t saVTable = { }; #endif // VTX_COMMON - #endif // VTX_SMARTAUDIO diff --git a/src/main/io/vtx_smartaudio.h b/src/main/io/vtx_smartaudio.h index e04a9dbf6..f4c15ae58 100644 --- a/src/main/io/vtx_smartaudio.h +++ b/src/main/io/vtx_smartaudio.h @@ -34,7 +34,6 @@ #define VTX_SMARTAUDIO_MIN_BAND 1 #define VTX_SMARTAUDIO_MIN_CHANNEL 1 - #define VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ 5000 //min freq in MHz #define VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ 5999 //max freq in MHz diff --git a/src/main/msc/usbd_storage_emfat.c b/src/main/msc/usbd_storage_emfat.c index 7d778ec06..608d5c58b 100644 --- a/src/main/msc/usbd_storage_emfat.c +++ b/src/main/msc/usbd_storage_emfat.c @@ -38,7 +38,6 @@ #include "msc/usbd_storage.h" #include "msc/usbd_storage_emfat.h" - #define STORAGE_LUN_NBR 1 static const uint8_t STORAGE_Inquirydata[] = diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index 694226e39..195c6c51f 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -25,7 +25,6 @@ ****************************************************************************** */ - /* Includes ------------------------------------------------------------------*/ #include #include diff --git a/src/main/msc/usbd_storage_sdio.c b/src/main/msc/usbd_storage_sdio.c index e424d1944..17c2f8f43 100644 --- a/src/main/msc/usbd_storage_sdio.c +++ b/src/main/msc/usbd_storage_sdio.c @@ -25,7 +25,6 @@ ****************************************************************************** */ - /* Includes ------------------------------------------------------------------*/ #include #include diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index 996b57e87..67155a316 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -158,7 +158,6 @@ #include "msp.h" - static const char * const flightControllerIdentifier = FC_FIRMWARE_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller. enum { @@ -1228,14 +1227,12 @@ case MSP_NAME: rpmDataAvailable = true; invalidPct = 10000; // 100.00% - #ifdef USE_DSHOT_TELEMETRY_STATS if (isDshotMotorTelemetryActive(i)) { invalidPct = getDshotTelemetryMotorInvalidPercent(i); } #endif - // Provide extended dshot telemetry if ((dshotTelemetryState.motorState[i].telemetryTypes & DSHOT_EXTENDED_TELEMETRY_MASK) != 0) { // Temperature Celsius [0, 1, ..., 255] in degree Celsius, just like Blheli_32 and KISS @@ -1813,7 +1810,6 @@ case MSP_NAME: sbufWriteU16(dst, flight3DConfig()->deadband3d_throttle); break; - case MSP_SENSOR_ALIGNMENT: { uint8_t gyroAlignment; #ifdef USE_MULTI_GYRO @@ -2189,7 +2185,6 @@ case MSP_NAME: return !unsupportedCommand; } - #ifdef USE_SIMPLIFIED_TUNING // Reads simplified PID tuning values from MSP buffer static void readSimplifiedPids(pidProfile_t* pidProfile, sbuf_t *src) diff --git a/src/main/msp/msp.h b/src/main/msp/msp.h index 9b04aa751..7392e0205 100644 --- a/src/main/msp/msp.h +++ b/src/main/msp/msp.h @@ -61,7 +61,6 @@ typedef void (*mspPostProcessFnPtr)(struct serialPort_s *port); // msp post proc typedef mspResult_e (*mspProcessCommandFnPtr)(mspDescriptor_t srcDesc, mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn); typedef void (*mspProcessReplyFnPtr)(mspPacket_t *cmd); - void mspInit(void); mspResult_e mspFcProcessCommand(mspDescriptor_t srcDesc, mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn); void mspFcProcessReply(mspPacket_t *reply); diff --git a/src/main/msp/msp_box.c b/src/main/msp/msp_box.c index b06de04a7..031793fd1 100644 --- a/src/main/msp/msp_box.c +++ b/src/main/msp/msp_box.c @@ -44,7 +44,6 @@ #include "msp_box.h" - // permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM! static const box_t boxes[CHECKBOX_ITEM_COUNT] = { { .boxId = BOXARM, .boxName = "ARM", .permanentId = 0 }, diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index 36a629641..1114ebdf3 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -245,7 +245,6 @@ // See MSP_API_VERSION and MSP_MIXER_CONFIG //DEPRECATED - #define MSP_IDENT 100 //out message mixerMode + multiwii version + protocol version + capability variable - #define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number #define MSP_RAW_IMU 102 //out message 9 DOF #define MSP_SERVO 103 //out message servos diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 9992c2499..391ca4ec1 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -1070,7 +1070,6 @@ static void osdRenderStatsBegin(void) osdStatsRenderingState.index = 0; } - // call repeatedly until it returns true which indicates that all stats have been rendered. static bool osdRenderStatsContinue(void) { @@ -1097,7 +1096,6 @@ static bool osdRenderStatsContinue(void) } } - bool renderedStat = false; while (osdStatsRenderingState.index < OSD_STAT_COUNT) { diff --git a/src/main/osd/osd.h b/src/main/osd/osd.h index e6ae3448b..7443dcb23 100644 --- a/src/main/osd/osd.h +++ b/src/main/osd/osd.h @@ -60,7 +60,6 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES]; #define OSD_PROFILE_FLAG(x) (1 << ((x) - 1 + OSD_PROFILE_BITS_POS)) #define OSD_PROFILE_1_FLAG OSD_PROFILE_FLAG(1) - #ifdef USE_OSD_PROFILES #define VISIBLE(x) osdElementVisible(x) #define VISIBLE_IN_OSD_PROFILE(item, profile) ((item) & ((OSD_PROFILE_1_FLAG) << ((profile)-1))) @@ -69,7 +68,6 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES]; #define VISIBLE_IN_OSD_PROFILE(item, profile) VISIBLE(item) #endif - // Character coordinate #define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31 #define OSD_POSITION_BIT_XHD 10 // extra bit used to extend X range in a backward compatible manner for HD displays diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index d5322055c..943980993 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -587,7 +587,6 @@ static uint8_t osdGetDirectionSymbolFromHeading(int heading) return SYM_ARROW_SOUTH + heading; } - /** * Converts altitude based on the current unit system. * @param meters Value in meters to convert diff --git a/src/main/pg/adc.c b/src/main/pg/adc.c index d10de7da9..b32de9545 100644 --- a/src/main/pg/adc.c +++ b/src/main/pg/adc.c @@ -34,7 +34,6 @@ #include "pg/adc.h" - PG_REGISTER_WITH_RESET_FN(adcConfig_t, adcConfig, PG_ADC_CONFIG, 0); void pgResetFn_adcConfig(adcConfig_t *adcConfig) diff --git a/src/main/pg/gyrodev.h b/src/main/pg/gyrodev.h index af81b4b37..b46d98ecb 100644 --- a/src/main/pg/gyrodev.h +++ b/src/main/pg/gyrodev.h @@ -20,7 +20,6 @@ #pragma once - #include #include "pg/pg.h" diff --git a/src/main/pg/motor.c b/src/main/pg/motor.c index 9272f36e9..e89a9fbca 100644 --- a/src/main/pg/motor.c +++ b/src/main/pg/motor.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include diff --git a/src/main/pg/pg_ids.h b/src/main/pg/pg_ids.h index 9e69a2aa1..90eb2703f 100644 --- a/src/main/pg/pg_ids.h +++ b/src/main/pg/pg_ids.h @@ -89,14 +89,12 @@ #define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight #define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight - // cleanflight v2 specific parameter group ids start at 256 #define PG_CURRENT_SENSOR_ADC_CONFIG 256 #define PG_CURRENT_SENSOR_VIRTUAL_CONFIG 257 #define PG_VOLTAGE_SENSOR_ADC_CONFIG 258 #define PG_VTX_SETTINGS_CONFIG 259 - // betaflight specific parameter group ids start at 500 #define PG_BETAFLIGHT_START 500 //#define PG_MODE_ACTIVATION_OPERATOR_CONFIG 500 removed @@ -161,13 +159,11 @@ #define PG_GIMBAL_TRACK_CONFIG 559 #define PG_BETAFLIGHT_END 559 - // OSD configuration (subject to change) #define PG_OSD_FONT_CONFIG 2047 #define PG_OSD_VIDEO_CONFIG 2046 #define PG_OSD_ELEMENT_CONFIG 2045 - // 4095 is currently the highest number that can be used for a PGN due to the top 4 bits of the 16 bit value being reserved for the version when the PG is stored in an EEPROM. #define PG_RESERVED_FOR_TESTING_1 4095 #define PG_RESERVED_FOR_TESTING_2 4094 diff --git a/src/main/pg/sdio.c b/src/main/pg/sdio.c index a8b5b4894..9d21ab6a7 100644 --- a/src/main/pg/sdio.c +++ b/src/main/pg/sdio.c @@ -57,7 +57,6 @@ #define SDIO_D3_PIN NONE #endif - PG_REGISTER_WITH_RESET_TEMPLATE(sdioConfig_t, sdioConfig, PG_SDIO_CONFIG, 0); PG_RESET_TEMPLATE(sdioConfig_t, sdioConfig, diff --git a/src/main/rx/cc2500_frsky_shared.h b/src/main/rx/cc2500_frsky_shared.h index 2ffd229f9..08acd8035 100644 --- a/src/main/rx/cc2500_frsky_shared.h +++ b/src/main/rx/cc2500_frsky_shared.h @@ -28,7 +28,6 @@ #define DEBUG_DATA_MISSING_PACKETS 1 #define DEBUG_DATA_BAD_FRAME 2 - #define SYNC_DELAY_MAX 9000 #define MAX_MISSING_PKT 100 diff --git a/src/main/rx/cc2500_frsky_x.c b/src/main/rx/cc2500_frsky_x.c index d2b660d7f..45bdc1896 100644 --- a/src/main/rx/cc2500_frsky_x.c +++ b/src/main/rx/cc2500_frsky_x.c @@ -276,7 +276,6 @@ static void frSkyXTelemetryWriteFrame(const smartPortPayload_t *payload) #endif #endif // USE_RX_FRSKY_SPI_TELEMETRY - void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet) { uint16_t c[8]; diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 5eb815b3e..7e50c0b7d 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -147,7 +147,6 @@ typedef struct crsfPayloadRcChannelsPacked_s crsfPayloadRcChannelsPacked_t; * - last channel packed with specified resolution */ - #if defined(USE_CRSF_LINK_STATISTICS) /* * 0x14 Link statistics diff --git a/src/main/rx/crsf.h b/src/main/rx/crsf.h index 37b6ac138..12ed53fd0 100644 --- a/src/main/rx/crsf.h +++ b/src/main/rx/crsf.h @@ -22,7 +22,6 @@ #include "rx/crsf_protocol.h" - #define CRSF_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) #define CRSF_PORT_MODE MODE_RXTX diff --git a/src/main/rx/cyrf6936_spektrum.c b/src/main/rx/cyrf6936_spektrum.c index f0dd5677f..b23a261e8 100644 --- a/src/main/rx/cyrf6936_spektrum.c +++ b/src/main/rx/cyrf6936_spektrum.c @@ -327,7 +327,6 @@ bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState rxSpiCommonIOInit(rxConfig); - rxRuntimeState->channelCount = DSM_MAX_CHANNEL_COUNT; extiConfig->ioConfig = IOCFG_IPD; diff --git a/src/main/rx/expresslrs.c b/src/main/rx/expresslrs.c index 3e8f576ad..c71a19693 100644 --- a/src/main/rx/expresslrs.c +++ b/src/main/rx/expresslrs.c @@ -150,12 +150,10 @@ static void phaseLockEprReset(void) memset(&eprState, 0, sizeof(eprState_t)); } - // // Phase Lock // - #define EPR_INTERNAL EPR_FIRST #define EPR_EXTERNAL EPR_SECOND diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 09f425956..80b57e07d 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -48,7 +48,6 @@ #include "rx/sbus_channels.h" #include "rx/fport.h" - #define FPORT_TIME_NEEDED_PER_FRAME_US 3000 #define FPORT_MAX_TELEMETRY_RESPONSE_DELAY_US 2000 #define FPORT_MIN_TELEMETRY_RESPONSE_DELAY_US 500 @@ -56,7 +55,6 @@ #define FPORT_TELEMETRY_MAX_CONSECUTIVE_TELEMETRY_FRAMES 2 - #define FPORT_FRAME_MARKER 0x7E #define FPORT_ESCAPE_CHAR 0x7D @@ -255,7 +253,6 @@ static uint8_t fportFrameStatus(rxRuntimeState_t *rxRuntimeState) uint8_t result = RX_FRAME_PENDING; - if (rxBufferReadIndex != rxBufferWriteIndex) { uint8_t bufferLength = rxBuffer[rxBufferReadIndex].length; uint8_t frameLength = rxBuffer[rxBufferReadIndex].data[0]; diff --git a/src/main/rx/ghst.c b/src/main/rx/ghst.c index cddf72562..62cf65ea1 100644 --- a/src/main/rx/ghst.c +++ b/src/main/rx/ghst.c @@ -112,7 +112,6 @@ static uint8_t telemetryBufLen = 0; * */ - // called from telemetry/ghst.c void ghstRxWriteTelemetryData(const void *const data, const int len) { diff --git a/src/main/rx/ghst_protocol.h b/src/main/rx/ghst_protocol.h index 9e656b23b..07e8d301a 100644 --- a/src/main/rx/ghst_protocol.h +++ b/src/main/rx/ghst_protocol.h @@ -121,7 +121,6 @@ typedef union ghstFrame_u { ghstFrameDef_t frame; } ghstFrame_t; - /* Pulses payload (channel data), for 4x 12-bit channels */ typedef struct ghstPayloadServo4_s { // 48 bits, or 6 bytes diff --git a/src/main/rx/ibus.c b/src/main/rx/ibus.c index 18e56d768..b76b523f7 100644 --- a/src/main/rx/ibus.c +++ b/src/main/rx/ibus.c @@ -82,7 +82,6 @@ static bool isValidIa6bIbusPacketLength(uint8_t length) return (length == IBUS_TELEMETRY_PACKET_LENGTH) || (length == IBUS_SERIAL_RX_PACKET_LENGTH); } - // Receive ISR callback static void ibusDataReceive(uint16_t c, void *data) { @@ -131,7 +130,6 @@ static void ibusDataReceive(uint16_t c, void *data) } } - static bool isChecksumOkIa6(void) { uint8_t offset; @@ -145,7 +143,6 @@ static bool isChecksumOkIa6(void) return chksum == rxsum; } - static bool checksumIsOk(void) { if (ibusModel == IBUS_MODEL_IA6 ) { @@ -155,7 +152,6 @@ static bool checksumIsOk(void) } } - static void updateChannelData(void) { uint8_t i; @@ -196,7 +192,6 @@ static uint8_t ibusFrameStatus(rxRuntimeState_t *rxRuntimeState) return frameStatus; } - static float ibusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan) { UNUSED(rxRuntimeState); @@ -223,7 +218,6 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState) bool portShared = false; #endif - rxBytesToIgnore = 0; serialPort_t *ibusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index 1284b2d58..e17029d97 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -36,7 +36,6 @@ * Jeti EX Bus -> Serial TX (connect directly) */ - #include #include @@ -56,7 +55,6 @@ #include "rx/rx.h" #include "rx/jetiexbus.h" - // // Serial driver for Jeti EX Bus receiver // @@ -65,7 +63,6 @@ #define JETIEXBUS_MIN_FRAME_GAP 1000 #define JETIEXBUS_CHANNEL_COUNT 16 // most Jeti TX transmit 16 channels - #define EXBUS_START_CHANNEL_FRAME (0x3E) #define EXBUS_START_REQUEST_FRAME (0x3D) #define EXBUS_JETIBOX_REQUEST (0x3B) @@ -74,8 +71,6 @@ #define EXBUS_CHANNELDATA_DATA_REQUEST (0x3E01) // Frame contains Channel Data, but with a request for data #define EXBUS_TELEMETRY_REQUEST (0x3D01) // Frame is a request Frame - - serialPort_t *jetiExBusPort; uint32_t jetiTimeStampRequest = 0; diff --git a/src/main/rx/msp.c b/src/main/rx/msp.c index d21d07c9e..f42477f6c 100644 --- a/src/main/rx/msp.c +++ b/src/main/rx/msp.c @@ -32,7 +32,6 @@ #include "rx/rx.h" #include "rx/msp.h" - static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT]; static bool rxMspFrameDone = false; static bool rxMspOverrideFrameDone = false; diff --git a/src/main/rx/msp_override.c b/src/main/rx/msp_override.c index 33eee1565..24665a8d8 100644 --- a/src/main/rx/msp_override.c +++ b/src/main/rx/msp_override.c @@ -27,7 +27,6 @@ #include "fc/rc_modes.h" #include "common/maths.h" - uint16_t rxMspOverrideReadRawRc(const rxRuntimeState_t *rxRuntimeState, const rxConfig_t *rxConfig, uint8_t chan) { uint16_t rxSample = (rxRuntimeState->rcReadRawFn)(rxRuntimeState, chan); diff --git a/src/main/rx/nrf24_h8_3d.c b/src/main/rx/nrf24_h8_3d.c index 30d55c670..15bd5e14a 100644 --- a/src/main/rx/nrf24_h8_3d.c +++ b/src/main/rx/nrf24_h8_3d.c @@ -44,7 +44,6 @@ #include "rx/rx_spi.h" #include "rx/nrf24_h8_3d.h" - /* * Deviation transmitter sends 345 bind packets, then starts sending data packets. * Packets are send at rate of at least one every 4 milliseconds, ie at least 250Hz. @@ -52,7 +51,6 @@ * Other transmitters may vary but should have similar characteristics. */ - /* * H8_3D Protocol * No auto acknowledgment diff --git a/src/main/rx/nrf24_inav.c b/src/main/rx/nrf24_inav.c index d9c383820..4c3ca3037 100644 --- a/src/main/rx/nrf24_inav.c +++ b/src/main/rx/nrf24_inav.c @@ -48,7 +48,6 @@ //#define NO_RF_CHANNEL_HOPPING //#define USE_BIND_ADDRESS_FOR_DATA_STATE - #define USE_AUTO_ACKKNOWLEDGEMENT /* diff --git a/src/main/rx/nrf24_syma.c b/src/main/rx/nrf24_syma.c index 07457a628..6bd436e06 100644 --- a/src/main/rx/nrf24_syma.c +++ b/src/main/rx/nrf24_syma.c @@ -48,7 +48,6 @@ * Other transmitters may vary but should have similar characteristics. */ - /* * SymaX Protocol * No auto acknowledgment diff --git a/src/main/rx/rc_stats.c b/src/main/rx/rc_stats.c index aa189a543..b415e1d69 100644 --- a/src/main/rx/rc_stats.c +++ b/src/main/rx/rc_stats.c @@ -42,7 +42,6 @@ timeUs_t fullThrottleTimeUs = 0; uint32_t fullThrottleCounter = 0; int8_t previousThrottlePercent = 0; - void rcStatsUpdate(timeUs_t currentTimeUs) { uint32_t deltaT = currentTimeUs - previousTimeUs; diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 956d8046a..77fdf27ca 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -72,7 +72,6 @@ #include "rx/targetcustomserial.h" #include "rx/msp_override.h" - const char rcChannelLetters[] = "AERT12345678abcdefgh"; static uint16_t rssi = 0; // range: [0;1023] diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 95393ff8e..3cea92b6d 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -41,7 +41,6 @@ #define CHANNEL_VALUE_TO_RXFAIL_STEP(channelValue) ((constrain(channelValue, PWM_PULSE_MIN, PWM_PULSE_MAX) - PWM_PULSE_MIN) / 25) #define MAX_RXFAIL_RANGE_STEP ((PWM_PULSE_MAX - PWM_PULSE_MIN) / 25) - typedef enum { RX_FRAME_PENDING = 0, RX_FRAME_COMPLETE = (1 << 0), diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 648b29f3f..f291bb5fe 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -103,7 +103,6 @@ static void spektrumDataReceive(uint16_t c, void *data) } } - uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT]; static uint8_t spektrumFrameStatus(rxRuntimeState_t *rxRuntimeState) @@ -290,7 +289,6 @@ void spektrumBind(rxConfig_t *rxConfig) } - // Release the bind pin to avoid interference with an actual rx pin, // when rxConfig->spektrum_bind_pin_override_ioTag is used. // This happens when the bind pin is connected in parallel to the rx pin. diff --git a/src/main/rx/spektrum.h b/src/main/rx/spektrum.h index c7c7defbc..256b42053 100644 --- a/src/main/rx/spektrum.h +++ b/src/main/rx/spektrum.h @@ -35,7 +35,6 @@ #define SPEKTRUM_BAUDRATE 115200 - // Spektrum system type values #define SPEKTRUM_DSM2_22 0x01 #define SPEKTRUM_DSM2_11 0x12 diff --git a/src/main/rx/srxl2.c b/src/main/rx/srxl2.c index 5f5accdcb..1b5366fc2 100644 --- a/src/main/rx/srxl2.c +++ b/src/main/rx/srxl2.c @@ -51,8 +51,6 @@ #define DEBUG_PRINTF(...) #endif - - #define SRXL2_MAX_CHANNELS 32 #define SRXL2_FRAME_PERIOD_US 11000 // 5500 for DSMR #define SRXL2_CHANNEL_SHIFT 2 @@ -143,7 +141,6 @@ bool srxl2ProcessHandshake(const Srxl2Header* header) return true; } - if (handshake->destinationDeviceId != ((FlightController << 4) | unitId)) { return true; } @@ -284,7 +281,6 @@ void srxl2Process(rxRuntimeState_t *rxRuntimeState) globalResult = RX_FRAME_DROPPED; } - static void srxl2DataReceive(uint16_t character, void *data) { UNUSED(data); diff --git a/src/main/rx/sumh.c b/src/main/rx/sumh.c index 89aa5c07b..c1c91eadc 100644 --- a/src/main/rx/sumh.c +++ b/src/main/rx/sumh.c @@ -59,7 +59,6 @@ static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT]; static serialPort_t *sumhPort; - // Receive ISR callback static void sumhDataReceive(uint16_t c, void *data) { diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 9fc85eff6..d96682750 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -52,7 +52,6 @@ #define XBUS_FRAME_SIZE_A1 27 #define XBUS_FRAME_SIZE_A2 35 - #define XBUS_RJ01_FRAME_SIZE 33 #define XBUS_RJ01_MESSAGE_LENGTH 30 #define XBUS_RJ01_OFFSET_BYTES 3 @@ -87,7 +86,6 @@ static uint8_t xBusFrameLength; static uint8_t xBusChannelCount; static uint8_t xBusProvider; - // Use max values for ram areas static volatile uint8_t xBusFrame[XBUS_FRAME_SIZE_A2]; //size 35 for 16 channels in xbus_Mode_B static uint16_t xBusChannelData[XBUS_RJ01_CHANNEL_COUNT]; @@ -112,7 +110,6 @@ static uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed) return seed; } - static void xBusUnpackModeBFrame(uint8_t offsetBytes) { // Calculate the CRC of the incoming frame diff --git a/src/main/sensors/acceleration_init.c b/src/main/sensors/acceleration_init.c index 25c2c9a4d..eb8bbf6e8 100644 --- a/src/main/sensors/acceleration_init.c +++ b/src/main/sensors/acceleration_init.c @@ -156,7 +156,6 @@ extern bool AccInflightCalibrationMeasurementDone; extern bool AccInflightCalibrationSavetoEEProm; extern bool AccInflightCalibrationActive; - bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) { accelerationSensor_e accHardware = ACC_NONE; diff --git a/src/main/sensors/acceleration_init.h b/src/main/sensors/acceleration_init.h index b900a452c..561741c22 100644 --- a/src/main/sensors/acceleration_init.h +++ b/src/main/sensors/acceleration_init.h @@ -24,7 +24,6 @@ #include "sensors/acceleration.h" - typedef struct accelerationRuntime_s { uint16_t accLpfCutHz; pt2Filter_t accFilter[XYZ_AXIS_COUNT]; diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 4900b2d11..cce06233d 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -383,7 +383,6 @@ typedef enum { BARO_STATE_COUNT } barometerState_e; - bool isBaroReady(void) { return baroReady; diff --git a/src/main/sensors/current.c b/src/main/sensors/current.c index 91d3aed00..61e542a3c 100644 --- a/src/main/sensors/current.c +++ b/src/main/sensors/current.c @@ -251,7 +251,6 @@ void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter) } #endif - #ifdef USE_MSP_CURRENT_METER #include "common/streambuf.h" diff --git a/src/main/sensors/current.h b/src/main/sensors/current.h index 351243d9d..8b86574b3 100644 --- a/src/main/sensors/current.h +++ b/src/main/sensors/current.h @@ -61,7 +61,6 @@ typedef enum { CURRENT_SENSOR_MSP } currentSensor_e; - // // ADC // @@ -104,7 +103,6 @@ typedef struct currentMeterESCState_s { int32_t amperage; // current read by current sensor in centiampere (1/100th A) } currentMeterESCState_t; - // // MSP // @@ -114,7 +112,6 @@ typedef struct currentMeterMSPState_s { int32_t amperage; // current read by current sensor in centiampere (1/100th A) } currentMeterMSPState_t; - // // Current Meter API // diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index bac354681..659028559 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -90,7 +90,6 @@ STATIC_UNIT_TESTED gyroSensor_t * const gyroSensorPtr = &gyro.gyroSensor1; STATIC_UNIT_TESTED gyroDev_t * const gyroDevPtr = &gyro.gyroSensor1.gyroDev; #endif - #define DEBUG_GYRO_CALIBRATION_VALUE 3 #define GYRO_OVERFLOW_TRIGGER_THRESHOLD 31980 // 97.5% full scale (1950dps for 2000dps gyro) diff --git a/src/main/sensors/gyro_init.c b/src/main/sensors/gyro_init.c index 553e63c3c..6ec8dc791 100644 --- a/src/main/sensors/gyro_init.c +++ b/src/main/sensors/gyro_init.c @@ -534,7 +534,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev) sensorsSet(SENSOR_GYRO); } - return gyroHardware; } @@ -721,7 +720,6 @@ void gyroSetTargetLooptime(uint8_t pidDenom) } } - gyroDev_t *gyroActiveDev(void) { return &ACTIVE_GYRO->gyroDev; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index f20936d6f..99b9b74e6 100644 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -46,7 +46,6 @@ #include "sensors/rangefinder.h" #include "sensors/sensors.h" - // requestedSensors is not actually used uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE }; uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE }; diff --git a/src/main/sensors/voltage.c b/src/main/sensors/voltage.c index ada22bb28..d0c572896 100644 --- a/src/main/sensors/voltage.c +++ b/src/main/sensors/voltage.c @@ -82,7 +82,6 @@ const uint8_t voltageMeterIds[] = { const uint8_t supportedVoltageMeterCount = ARRAYLEN(voltageMeterIds); - // // ADC/ESC shared // @@ -146,7 +145,6 @@ void pgResetFn_voltageSensorADCConfig(voltageSensorADCConfig_t *instance) } } - static const uint8_t voltageMeterAdcChannelMap[] = { ADC_BATTERY, #ifdef ADC_POWER_12V @@ -261,8 +259,6 @@ typedef struct voltageMeterESCState_s { static voltageMeterESCState_t voltageMeterESCState; #endif - - void voltageMeterESCInit(void) { #ifdef USE_ESC_SENSOR @@ -315,7 +311,6 @@ void voltageMeterESCReadCombined(voltageMeter_t *voltageMeter) // This API is used by MSP, for configuration/status. // - // the order of these much match the indexes in voltageSensorADC_e const uint8_t voltageMeterADCtoIDMap[MAX_VOLTAGE_SENSOR_ADC] = { VOLTAGE_METER_ID_BATTERY_1, diff --git a/src/main/sensors/voltage.h b/src/main/sensors/voltage.h index 0e5aed5f5..b612ae76f 100644 --- a/src/main/sensors/voltage.h +++ b/src/main/sensors/voltage.h @@ -59,7 +59,6 @@ typedef struct voltageMeter_s { bool lowVoltageCutoff; } voltageMeter_t; - // // sensors // @@ -69,7 +68,6 @@ typedef enum { VOLTAGE_SENSOR_TYPE_ESC } voltageSensorType_e; - // // adc sensors // @@ -96,7 +94,6 @@ typedef enum { VOLTAGE_SENSOR_ADC_5V = 3 } voltageSensorADC_e; // see also voltageMeterADCtoIDMap - typedef struct voltageSensorADCConfig_s { uint8_t vbatscale; // adjust this to match battery voltage to reported value uint8_t vbatresdivval; // resistor divider R2 (default NAZE 10(K)) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index a143df041..6355f2fe9 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -85,7 +85,6 @@ In the future we can move to specific drivers being added only - to save flash space. */ - // normalize serial ports definitions #include "serial_post.h" @@ -566,7 +565,6 @@ #undef USE_CMS_GPS_RESCUE_MENU #endif - #if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) #ifndef EEPROM_SIZE #define EEPROM_SIZE 4096 diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index ce387baf7..99f3a6bf7 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -396,13 +396,11 @@ #define USE_GPS_RESCUE #endif // USE_GPS - #if (defined(USE_OSD_HD) || defined(USE_OSD_SD)) && !defined(USE_OSD) // If either USE_OSD_SD for USE_OSD_HD are defined, ensure that USE_OSD is also defined #define USE_OSD #endif - #if defined(USE_OSD) #if !defined(USE_OSD_HD) && !defined(USE_OSD_SD) diff --git a/src/main/target/serial_post.h b/src/main/target/serial_post.h index b7af5b464..ffc756925 100644 --- a/src/main/target/serial_post.h +++ b/src/main/target/serial_post.h @@ -19,7 +19,6 @@ * If not, see . */ - /* This file is automatically generated by src/utils/gen-serial.py script from src/utils/templates/serial_post.h jinja2 template. Do not modify this file directly, your changes will be eventually lost. @@ -112,7 +111,6 @@ Configuration used: // 0 if no port is defined #define SERIAL_UART_MAX (SERIAL_UART_MASK ? LOG2(SERIAL_UART_MASK) + 1 : 0) - // enable USE_INVERTED first, before normalization #if !defined(USE_INVERTER) && (INVERTER_PIN_UART1 || INVERTER_PIN_UART2 || INVERTER_PIN_UART3 || INVERTER_PIN_UART4 || INVERTER_PIN_UART5 || INVERTER_PIN_UART6 || INVERTER_PIN_UART7 || INVERTER_PIN_UART8 || INVERTER_PIN_UART9 || INVERTER_PIN_UART10) # define USE_INVERTER @@ -402,7 +400,6 @@ Configuration used: // 0 if no port is defined #define SERIAL_LPUART_MAX (SERIAL_LPUART_MASK ? LOG2(SERIAL_LPUART_MASK) + 1 : 0) - // Normalize LPUART TX/RX #if SERIAL_LPUART1_USED && !defined(LPUART1_RX_PIN) # define LPUART1_RX_PIN NONE @@ -505,8 +502,6 @@ Configuration used: // 0 if no port is defined #define SERIAL_VCP_MAX (SERIAL_VCP_MASK ? LOG2(SERIAL_VCP_MASK) + 1 : 0) - - // normalize USE_x after all ports are enumerated (x_COUNT of dependencies must be available) #if !defined(USE_UART) && (SERIAL_UART_COUNT || SERIAL_LPUART_COUNT) # define USE_UART diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 09c628496..cbe882c59 100644 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -73,7 +73,6 @@ #include "crsf.h" - #define CRSF_CYCLETIME_US 100000 // 100ms, 10 Hz #define CRSF_DEVICEINFO_VERSION 0x01 #define CRSF_DEVICEINFO_PARAMETER_COUNT 0 @@ -515,7 +514,6 @@ void crsfFrameDeviceInfo(sbuf_t *dst) *lengthPtr = sbufPtr(dst) - lengthPtr; } - #if defined(USE_CRSF_V3) void crsfFrameSpeedNegotiationResponse(sbuf_t *dst, bool reply) { diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 54445b635..343777bfe 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -59,7 +59,6 @@ #include "platform.h" - #ifdef USE_TELEMETRY_HOTT #include "build/build_config.h" diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h index 46d3b85e7..a2e446d3c 100644 --- a/src/main/telemetry/hott.h +++ b/src/main/telemetry/hott.h @@ -74,7 +74,6 @@ typedef enum { HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE = (1 << 7) } hottEamAlarm2Flag_e; - // // Messages // @@ -102,7 +101,6 @@ typedef enum { //Graupner #33620 Electric Air Module #define HOTT_TELEMETRY_EAM_SENSOR_ID 0x8e - #define HOTT_EAM_SENSOR_TEXT_ID 0xE0 // Electric Air Module ID #define HOTT_GPS_SENSOR_TEXT_ID 0xA0 // GPS Module ID @@ -236,7 +234,6 @@ typedef struct HOTT_VARIO_MSG_s { // C m/s negative difference // A m/3s negative difference - uint8_t sensor_id; //#04 constant value 0x90 uint8_t alarm_invers1; //#05 Inverse display (alarm?) bitmask //TODO: more info diff --git a/src/main/telemetry/ibus.c b/src/main/telemetry/ibus.c index 9f1c81716..e302d0a83 100644 --- a/src/main/telemetry/ibus.c +++ b/src/main/telemetry/ibus.c @@ -62,7 +62,6 @@ #include "telemetry/ibus_shared.h" #include "telemetry/telemetry.h" - #define IBUS_TASK_PERIOD_US (1000) #define IBUS_UART_MODE (MODE_RXTX) @@ -74,7 +73,6 @@ #define IBUS_MAX_RX_LEN (4) #define IBUS_RX_BUF_LEN (IBUS_MAX_RX_LEN) - static serialPort_t *ibusSerialPort = NULL; static const serialPortConfig_t *ibusSerialPortConfig; @@ -87,15 +85,12 @@ static portSharing_e ibusPortSharing; static uint8_t ibusReceiveBuffer[IBUS_RX_BUF_LEN] = { 0x0 }; - - static void pushOntoTail(uint8_t buffer[IBUS_MIN_LEN], size_t bufferLength, uint8_t value) { memmove(buffer, buffer + 1, bufferLength - 1); ibusReceiveBuffer[bufferLength - 1] = value; } - void initIbusTelemetry(void) { ibusSerialPortConfig = findSerialPortConfig(FUNCTION_TELEMETRY_IBUS); @@ -103,7 +98,6 @@ void initIbusTelemetry(void) ibusTelemetryEnabled = false; } - void handleIbusTelemetry(void) { if (!ibusTelemetryEnabled) { @@ -126,7 +120,6 @@ void handleIbusTelemetry(void) } } - bool checkIbusTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ibusPortSharing); @@ -145,7 +138,6 @@ bool checkIbusTelemetryState(void) return true; } - void configureIbusTelemetryPort(void) { if (!ibusSerialPortConfig) { @@ -168,7 +160,6 @@ void configureIbusTelemetryPort(void) outboundBytesToIgnoreOnRxCount = 0; } - void freeIbusTelemetryPort(void) { closeSerialPort(ibusSerialPort); diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index d3319c04c..3e040a323 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -27,7 +27,6 @@ * clarify the protocol. */ - #include #include #include @@ -57,7 +56,6 @@ static uint16_t calculateChecksum(const uint8_t *ibusPacket); #include "flight/position.h" #include "io/gps.h" - #define IBUS_TEMPERATURE_OFFSET 400 #define INVALID_IBUS_ADDRESS 0 #define IBUS_BUFFSIZE 33 // biggest iBus message seen so far + 1 @@ -129,7 +127,6 @@ static serialPort_t *ibusSerialPort = NULL; static ibusAddress_t ibusBaseAddress = INVALID_IBUS_ADDRESS; static uint8_t sendBuffer[IBUS_BUFFSIZE]; - static void setValue(uint8_t* bufferPtr, uint8_t sensorType, uint8_t length); static uint8_t getSensorID(ibusAddress_t address) @@ -226,7 +223,6 @@ static uint16_t getTemperature(void) return temperature + IBUS_TEMPERATURE_OFFSET; } - static uint16_t getFuel(void) { uint16_t fuel = 0; @@ -291,8 +287,6 @@ static void setCombinedFrame(uint8_t* bufferPtr, const uint8_t* structure, uint8 } #endif - - #if defined(USE_GPS) static bool setGPS(uint8_t sensorType, ibusTelemetry_s* value) { @@ -488,14 +482,12 @@ uint8_t respondToIbusRequest(uint8_t const * const ibusPacket) return transmitIbusPacket(); } - void initSharedIbusTelemetry(serialPort_t *port) { ibusSerialPort = port; ibusBaseAddress = INVALID_IBUS_ADDRESS; } - #endif //defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS) static uint16_t calculateChecksum(const uint8_t *ibusPacket) diff --git a/src/main/telemetry/ibus_shared.h b/src/main/telemetry/ibus_shared.h index 2723f7f22..c31b99c7a 100644 --- a/src/main/telemetry/ibus_shared.h +++ b/src/main/telemetry/ibus_shared.h @@ -85,5 +85,4 @@ void initSharedIbusTelemetry(serialPort_t * port); #endif //defined(TELEMETRY) && defined(TELEMETRY_IBUS) - bool isChecksumOkIa6b(const uint8_t *ibusPacket, const uint8_t length); diff --git a/src/main/telemetry/jetiexbus.c b/src/main/telemetry/jetiexbus.c index e952083a4..07dc7fe2e 100644 --- a/src/main/telemetry/jetiexbus.c +++ b/src/main/telemetry/jetiexbus.c @@ -39,7 +39,6 @@ #include "drivers/serial_uart.h" #include "drivers/time.h" - #include "flight/position.h" #include "flight/imu.h" @@ -171,7 +170,6 @@ union{ char vBytes[4]; } exGps; - #define JETI_EX_SENSOR_COUNT (ARRAYLEN(jetiExSensors)) static uint8_t jetiExBusTelemetryFrame[40]; @@ -302,7 +300,6 @@ uint32_t calcGpsDDMMmmm(int32_t value, bool isLong) return exGps.vInt; } - int32_t getSensorValue(uint8_t sensor) { switch (sensor) { diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 222d8753d..d8ec72b87 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -79,7 +79,6 @@ #include "telemetry/telemetry.h" #include "telemetry/ltm.h" - #define TELEMETRY_LTM_INITIAL_PORT_MODE MODE_TX #define LTM_CYCLETIME 100 diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index c9c79d919..23b995476 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -129,7 +129,6 @@ static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum) return 0; } - static void mavlinkSerialWrite(uint8_t * buf, uint16_t length) { for (int i = 0; i < length; i++) @@ -146,7 +145,6 @@ static int16_t headingOrScaledMilliAmpereHoursDrawn(void) return DECIDEGREES_TO_DEGREES(attitude.values.yaw); } - void freeMAVLinkTelemetryPort(void) { closeSerialPort(mavlinkPort); @@ -433,7 +431,6 @@ void mavlinkSendHUDAndHeartbeat(void) msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg); mavlinkSerialWrite(mavBuffer, msgLength); - uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; if (ARMING_FLAG(ARMED)) mavModes |= MAV_MODE_FLAG_SAFETY_ARMED; diff --git a/src/main/telemetry/msp_shared.c b/src/main/telemetry/msp_shared.c index 3d4a85718..b0993d175 100644 --- a/src/main/telemetry/msp_shared.c +++ b/src/main/telemetry/msp_shared.c @@ -40,7 +40,6 @@ #include "telemetry/msp_shared.h" #include "telemetry/smartport.h" - /* --------------------------------------------------------------- How MSP frames are sent over CRSF: diff --git a/src/main/telemetry/srxl.c b/src/main/telemetry/srxl.c index a992078e5..304b670bd 100644 --- a/src/main/telemetry/srxl.c +++ b/src/main/telemetry/srxl.c @@ -154,7 +154,6 @@ bool srxlFrameQos(sbuf_t *dst, timeUs_t currentTimeUs) return true; } - /* typedef struct { @@ -676,7 +675,6 @@ static bool srxlFrameVTX(sbuf_t *dst, timeUs_t currentTimeUs) } #endif // USE_SPEKTRUM_VTX_TELEMETRY && USE_SPEKTRUM_VTX_CONTROL && USE_VTX_COMMON - // Schedule array to decide how often each type of frame is sent // The frames are scheduled in sets of 3 frames, 2 mandatory and 1 user frame. // The user frame type is cycled for each set. @@ -729,7 +727,6 @@ const srxlScheduleFnPtr srxlScheduleFuncs[SRXL_TOTAL_COUNT] = { #endif }; - static void processSrxl(timeUs_t currentTimeUs) { static uint8_t srxlScheduleIndex = 0; diff --git a/src/platform/APM32/bus_spi_apm32.c b/src/platform/APM32/bus_spi_apm32.c index 82c2a01d6..831796331 100644 --- a/src/platform/APM32/bus_spi_apm32.c +++ b/src/platform/APM32/bus_spi_apm32.c @@ -137,7 +137,6 @@ void spiInternalResetStream(dmaChannelDescriptor_t *descriptor) DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); } - FAST_CODE static bool spiInternalReadWriteBufPolled(SPI_TypeDef *instance, const uint8_t *txData, uint8_t *rxData, int len) { while (len) { diff --git a/src/platform/APM32/dshot_bitbang.c b/src/platform/APM32/dshot_bitbang.c index 3e20081e9..d128aec8f 100644 --- a/src/platform/APM32/dshot_bitbang.c +++ b/src/platform/APM32/dshot_bitbang.c @@ -88,7 +88,6 @@ BB_INPUT_BUFFER_ATTRIBUTE uint16_t bbInputBuffer[DSHOT_BB_PORT_IP_BUF_CACHE_ALIG uint8_t bbPuPdMode; FAST_DATA_ZERO_INIT timeUs_t dshotFrameUs; - const timerHardware_t bbTimerHardware[] = { #if defined(APM32F4) DEF_TIM(TMR8, CH1, NONE, 0, 1), @@ -682,7 +681,6 @@ static void bbPostInit(void) return; } - bbMotors[motorIndex].enabled = true; // Fill in motors structure for 4way access (XXX Should be refactored) diff --git a/src/platform/APM32/eint_apm32.c b/src/platform/APM32/eint_apm32.c index 8d8543d82..c3e0d8bf9 100644 --- a/src/platform/APM32/eint_apm32.c +++ b/src/platform/APM32/eint_apm32.c @@ -146,7 +146,6 @@ void EXTIEnable(IO_t io) #endif } - void EXTIDisable(IO_t io) { #if defined(APM32F4) @@ -186,7 +185,6 @@ void EXTI_IRQHandler(uint32_t mask) struct dummy \ /**/ - _EXTI_IRQ_HANDLER(EINT0_IRQHandler, 0x0001); _EXTI_IRQ_HANDLER(EINT1_IRQHandler, 0x0002); #if defined(APM32F4) diff --git a/src/platform/APM32/pwm_output_apm32.c b/src/platform/APM32/pwm_output_apm32.c index 35a6af271..7a3ce77f3 100644 --- a/src/platform/APM32/pwm_output_apm32.c +++ b/src/platform/APM32/pwm_output_apm32.c @@ -35,7 +35,6 @@ #include "pg/motor.h" - FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS]; static void pwmOCConfig(TMR_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output) diff --git a/src/platform/APM32/pwm_output_dshot_apm32.c b/src/platform/APM32/pwm_output_dshot_apm32.c index 67aaa2ab5..02189569f 100644 --- a/src/platform/APM32/pwm_output_dshot_apm32.c +++ b/src/platform/APM32/pwm_output_dshot_apm32.c @@ -124,7 +124,6 @@ FAST_CODE static void pwmDshotSetDirectionInput( } #endif - FAST_CODE void pwmCompleteDshotMotorUpdate(void) { /* If there is a dshot command loaded up, time it correctly with motor update*/ diff --git a/src/platform/APM32/serial_uart_apm32.c b/src/platform/APM32/serial_uart_apm32.c index 399ff8532..43344e231 100644 --- a/src/platform/APM32/serial_uart_apm32.c +++ b/src/platform/APM32/serial_uart_apm32.c @@ -99,7 +99,6 @@ void uartReconfigure(uartPort_t *uartPort) #endif uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->rxDMAHandle); DAL_DMA_Init(&uartPort->rxDMAHandle); /* Associate the initialized DMA handle to the UART handle */ @@ -143,7 +142,6 @@ void uartReconfigure(uartPort_t *uartPort) uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->txDMAHandle); DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle); if (status != DAL_OK) { diff --git a/src/platform/APM32/startup/apm32f4xx_dal_cfg.h b/src/platform/APM32/startup/apm32f4xx_dal_cfg.h index 06e3c931c..b35e0d93a 100644 --- a/src/platform/APM32/startup/apm32f4xx_dal_cfg.h +++ b/src/platform/APM32/startup/apm32f4xx_dal_cfg.h @@ -23,7 +23,6 @@ * and limitations under the License. */ - /* Define to prevent recursive inclusion */ #ifndef APM32F4xx_DAL_CFG_H #define APM32F4xx_DAL_CFG_H diff --git a/src/platform/APM32/startup/system_apm32f4xx.h b/src/platform/APM32/startup/system_apm32f4xx.h index 8284e7fde..1c7476a51 100644 --- a/src/platform/APM32/startup/system_apm32f4xx.h +++ b/src/platform/APM32/startup/system_apm32f4xx.h @@ -51,7 +51,6 @@ * @} */ - /** @addtogroup APM32F4xx_System_Exported_types * @{ */ diff --git a/src/platform/APM32/timer_apm32f4xx.c b/src/platform/APM32/timer_apm32f4xx.c index 7ab390fce..df020c0af 100644 --- a/src/platform/APM32/timer_apm32f4xx.c +++ b/src/platform/APM32/timer_apm32f4xx.c @@ -32,7 +32,6 @@ #include "drivers/rcc.h" #include "drivers/timer.h" - const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TMR1, .rcc = RCC_APB2(TMR1), .inputIrq = TMR1_CC_IRQn}, { .TIMx = TMR2, .rcc = RCC_APB1(TMR2), .inputIrq = TMR2_IRQn}, @@ -174,7 +173,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { }; #endif - /* need a mapping from dma and timers to pins, and the values should all be set here to the dmaMotors array. this mapping could be used for both these motors and for led strip. diff --git a/src/platform/APM32/transponder_ir_io_apm32.c b/src/platform/APM32/transponder_ir_io_apm32.c index 09d48e7dc..738f88f33 100644 --- a/src/platform/APM32/transponder_ir_io_apm32.c +++ b/src/platform/APM32/transponder_ir_io_apm32.c @@ -148,7 +148,6 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder) return; } - RCC_ClockCmd(timerRCC(timer), ENABLE); /* PWM1 Mode configuration: Channel1 */ @@ -260,7 +259,6 @@ void transponderIrDisable(void) DAL_TMR_PWM_Stop(&TmrHandle, timerChannel); } - IOInit(transponderIO, OWNER_TRANSPONDER, 0); #ifdef TRANSPONDER_INVERTED diff --git a/src/platform/APM32/usb/msc/usbd_msc_descriptor.c b/src/platform/APM32/usb/msc/usbd_msc_descriptor.c index 1a1bc7d4c..48059a768 100644 --- a/src/platform/APM32/usb/msc/usbd_msc_descriptor.c +++ b/src/platform/APM32/usb/msc/usbd_msc_descriptor.c @@ -563,7 +563,6 @@ static USBD_DESC_INFO_T USBD_MSC_ProductStrDescHandler(uint8_t usbSpeed) descInfo = USBD_DESC_Ascii2Unicode((uint8_t*)USBD_PRODUCT_FS_STR); } - return descInfo; } diff --git a/src/platform/APM32/usb/usbd_board_apm32f4.c b/src/platform/APM32/usb/usbd_board_apm32f4.c index 058f8404c..f17db3b4d 100644 --- a/src/platform/APM32/usb/usbd_board_apm32f4.c +++ b/src/platform/APM32/usb/usbd_board_apm32f4.c @@ -108,10 +108,8 @@ void OTG_HS1_WKUP_IRQHandler(void) /* Clear EINT pending Bit*/ __DAL_USB_OTG_HS_WAKEUP_EINT_CLEAR_FLAG(); #endif - } - /** * @brief Initializes the PCD MSP * diff --git a/src/platform/APM32/usb/vcp/usbd_cdc_vcp.c b/src/platform/APM32/usb/vcp/usbd_cdc_vcp.c index f7f546822..bf4dc117d 100644 --- a/src/platform/APM32/usb/vcp/usbd_cdc_vcp.c +++ b/src/platform/APM32/usb/vcp/usbd_cdc_vcp.c @@ -61,7 +61,6 @@ static USBD_STA_T USBD_CDC_ItfSendEnd(uint8_t epNum, uint8_t *buffer, uint32_t * static USBD_STA_T USBD_CDC_ItfReceive(uint8_t *buffer, uint32_t *length); static USBD_STA_T USBD_CDC_ItfSOF(void); - /* USB CDC interface handler */ USBD_CDC_INTERFACE_T USBD_CDC_INTERFACE = { diff --git a/src/platform/APM32/usb/vcp/usbd_cdc_vcp.h b/src/platform/APM32/usb/vcp/usbd_cdc_vcp.h index 9ad4f63d2..70697fb53 100644 --- a/src/platform/APM32/usb/vcp/usbd_cdc_vcp.h +++ b/src/platform/APM32/usb/vcp/usbd_cdc_vcp.h @@ -60,7 +60,6 @@ uint32_t CDC_BaudRate(void); void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context); void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context); - #ifdef __cplusplus extern "C" { #endif diff --git a/src/platform/AT32/adc_at32f43x.c b/src/platform/AT32/adc_at32f43x.c index 9e96c61bf..46b3ae714 100644 --- a/src/platform/AT32/adc_at32f43x.c +++ b/src/platform/AT32/adc_at32f43x.c @@ -64,7 +64,6 @@ #include "pg/adc.h" - const adcDevice_t adcHardware[ADCDEV_COUNT] = { { .ADCx = ADC1, @@ -192,7 +191,6 @@ void setScalingFactors(void) adcTSSlopeK = lrintf(-3300.0f*1000.0f/4095.0f/TEMPSENSOR_SLOPE); } - /** * Setup the ADC so that it's running in the background and ready to * provide channel data @@ -332,7 +330,6 @@ void adcInit(const adcConfig_t *config) adc_common_config(&adc_common_struct); - // Only adc1 will have any channels assigned to it after the code above, so this can be simplified int dmaBufferIndex = 0; @@ -349,7 +346,6 @@ void adcInit(const adcConfig_t *config) // Set the oversampling ratio and matching shift adc_oversample_ratio_shift_set(adc->ADCx, ADC_OVERSAMPLE_RATIO_64, ADC_OVERSAMPLE_SHIFT_6); - #ifdef USE_DMA_SPEC // Setup the DMA channel so that data is automatically and continuously transferred from the ADC output register diff --git a/src/platform/AT32/bus_i2c_atbsp.c b/src/platform/AT32/bus_i2c_atbsp.c index 52cd0d959..a8d1bf647 100644 --- a/src/platform/AT32/bus_i2c_atbsp.c +++ b/src/platform/AT32/bus_i2c_atbsp.c @@ -197,7 +197,6 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t } } - if (status != I2C_OK) { return i2cHandleHardwareFailure(device); } diff --git a/src/platform/AT32/bus_i2c_atbsp_init.c b/src/platform/AT32/bus_i2c_atbsp_init.c index 7849d8095..79582e0ad 100644 --- a/src/platform/AT32/bus_i2c_atbsp_init.c +++ b/src/platform/AT32/bus_i2c_atbsp_init.c @@ -131,7 +131,6 @@ void i2cInit(I2CDevice device) IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, pDev->sclAF); IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, pDev->sdaAF); - // Init I2C peripheral i2c_handle_type *pHandle = &pDev->handle; memset(pHandle, 0, sizeof(*pHandle)); diff --git a/src/platform/AT32/bus_spi_at32bsp.c b/src/platform/AT32/bus_spi_at32bsp.c index 11f9d1015..6efa9c04a 100644 --- a/src/platform/AT32/bus_spi_at32bsp.c +++ b/src/platform/AT32/bus_spi_at32bsp.c @@ -144,7 +144,6 @@ static bool spiInternalReadWriteBufPolled(spi_type *instance, const uint8_t *txD while (spi_i2s_flag_get(instance, SPI_I2S_TDBE_FLAG) == RESET); spi_i2s_data_transmit(instance, b); - while (spi_i2s_flag_get(instance, SPI_I2S_RDBF_FLAG) == RESET); b = (uint8_t)spi_i2s_data_receive(instance); diff --git a/src/platform/AT32/dshot_bitbang.c b/src/platform/AT32/dshot_bitbang.c index 52ee1b00f..a57b65f4c 100644 --- a/src/platform/AT32/dshot_bitbang.c +++ b/src/platform/AT32/dshot_bitbang.c @@ -673,7 +673,6 @@ static void bbPostInit(void) return; } - bbMotors[motorIndex].enabled = true; // Fill in motors structure for 4way access (XXX Should be refactored) diff --git a/src/platform/AT32/light_ws2811strip_at32f43x.c b/src/platform/AT32/light_ws2811strip_at32f43x.c index 98b1633b0..1adfd990d 100644 --- a/src/platform/AT32/light_ws2811strip_at32f43x.c +++ b/src/platform/AT32/light_ws2811strip_at32f43x.c @@ -123,7 +123,6 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag) tmr_clock_source_div_set(timer,TMR_CLOCK_DIV1); tmr_cnt_dir_set(timer,TMR_COUNT_UP); - tmr_output_config_type tmr_OCInitStruct; tmr_output_default_para_init(&tmr_OCInitStruct); tmr_OCInitStruct.oc_mode= TMR_OUTPUT_CONTROL_PWM_MODE_A; @@ -141,7 +140,6 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag) tmr_channel_value_set(timer, (timerHardware->channel-1)*2, 0); tmr_output_channel_config(timer,(timerHardware->channel-1)*2, &tmr_OCInitStruct); - tmr_period_buffer_enable(timer, TRUE); tmr_output_channel_buffer_enable(timer, ((timerHardware->channel-1) * 2), TRUE); diff --git a/src/platform/AT32/pwm_output_at32bsp.c b/src/platform/AT32/pwm_output_at32bsp.c index d93a51c19..8be48f317 100644 --- a/src/platform/AT32/pwm_output_at32bsp.c +++ b/src/platform/AT32/pwm_output_at32bsp.c @@ -66,7 +66,6 @@ void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware, inversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output ); - tmr_output_enable(timerHardware->tim, TRUE); tmr_counter_enable(timerHardware->tim, TRUE); diff --git a/src/platform/AT32/pwm_output_dshot.c b/src/platform/AT32/pwm_output_dshot.c index 770da197a..ddaf7ed3e 100644 --- a/src/platform/AT32/pwm_output_dshot.c +++ b/src/platform/AT32/pwm_output_dshot.c @@ -207,7 +207,6 @@ FAST_CODE void pwmDshotSetDirectionOutput( } - #ifdef USE_DSHOT_TELEMETRY /** * Set the timer and dma of the specified motor for use as an input @@ -548,7 +547,6 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m motor->dmaRef = dmaRef; - #ifdef USE_DSHOT_TELEMETRY motor->dshotTelemetryDeadtimeUs = DSHOT_TELEMETRY_DEADTIME_US + 1000000 * (16 * MOTOR_BITLENGTH) / getDshotHz(pwmProtocolType); diff --git a/src/platform/AT32/serial_uart_at32bsp.c b/src/platform/AT32/serial_uart_at32bsp.c index 0ba46faf5..f2f623372 100644 --- a/src/platform/AT32/serial_uart_at32bsp.c +++ b/src/platform/AT32/serial_uart_at32bsp.c @@ -239,7 +239,6 @@ void uartTryStartTxDMA(uartPort_t *s) } #endif - static void handleUsartTxDma(uartPort_t *s) { uartTryStartTxDMA(s); diff --git a/src/platform/AT32/serial_uart_at32f43x.c b/src/platform/AT32/serial_uart_at32f43x.c index 86a786ee7..61733f526 100644 --- a/src/platform/AT32/serial_uart_at32f43x.c +++ b/src/platform/AT32/serial_uart_at32f43x.c @@ -310,7 +310,6 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = { }, #endif - #ifdef USE_UART8 { .identifier = SERIAL_PORT_UART8, diff --git a/src/platform/AT32/startup/at32f435_437.h b/src/platform/AT32/startup/at32f435_437.h index e0dba5dad..05b26f4ac 100644 --- a/src/platform/AT32/startup/at32f435_437.h +++ b/src/platform/AT32/startup/at32f435_437.h @@ -35,7 +35,6 @@ extern "C" { #pragma anon_unions #endif - /** @addtogroup CMSIS * @{ */ diff --git a/src/platform/AT32/startup/at32f435_437_conf.h b/src/platform/AT32/startup/at32f435_437_conf.h index 13f40c650..cad13810f 100644 --- a/src/platform/AT32/startup/at32f435_437_conf.h +++ b/src/platform/AT32/startup/at32f435_437_conf.h @@ -30,7 +30,6 @@ extern "C" { #endif - #ifndef NULL #ifdef __cplusplus #define NULL 0 diff --git a/src/platform/AT32/target/AT32F435G/target.h b/src/platform/AT32/target/AT32F435G/target.h index 9e23368a4..2399974ad 100644 --- a/src/platform/AT32/target/AT32F435G/target.h +++ b/src/platform/AT32/target/AT32F435G/target.h @@ -64,7 +64,6 @@ #define USE_EXTI #define USE_GYRO_EXTI - #define USE_I2C #define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_2 diff --git a/src/platform/AT32/target/AT32F435M/target.h b/src/platform/AT32/target/AT32F435M/target.h index b446ca412..1a25cb9f3 100644 --- a/src/platform/AT32/target/AT32F435M/target.h +++ b/src/platform/AT32/target/AT32F435M/target.h @@ -64,7 +64,6 @@ #define USE_EXTI #define USE_GYRO_EXTI - #define USE_I2C #define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_2 diff --git a/src/platform/AT32/timer_at32f43x.c b/src/platform/AT32/timer_at32f43x.c index 1e4822215..8a4e39004 100644 --- a/src/platform/AT32/timer_at32f43x.c +++ b/src/platform/AT32/timer_at32f43x.c @@ -30,7 +30,6 @@ #include "drivers/rcc.h" #include "drivers/timer.h" - const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TMR1, .rcc = RCC_APB2(TMR1), .inputIrq = TMR1_CH_IRQn }, { .TIMx = TMR2, .rcc = RCC_APB1(TMR2), .inputIrq = TMR2_GLOBAL_IRQn }, diff --git a/src/platform/AT32/timer_def.h b/src/platform/AT32/timer_def.h index f92a619ad..cc60f8471 100644 --- a/src/platform/AT32/timer_def.h +++ b/src/platform/AT32/timer_def.h @@ -162,7 +162,6 @@ #define DEF_TIM_CHANNEL(ch) CONCAT(DEF_TIM_CHANNEL__, DEF_TIM_CH_GET(ch)) #define DEF_TIM_CHANNEL__D(chan_n, n_channel) chan_n - #define DEF_TIM_DMA_CHANNEL(variant, timch) \ CONCAT(DEF_TIM_DMA_CHANNEL__, DEF_TIM_DMA_GET(variant, timch)) #define DEF_TIM_DMA_CHANNEL__D(dma_n, channel_n) (dmaResource_t *)DMA ## dma_n ## _CHANNEL ## channel_n @@ -176,7 +175,6 @@ #define DEF_TIM_DMA_HANDLER__D(dma_n, channel_n) DMA ## dma_n ## _CH ## channel_n ## _HANDLER #define DEF_TIM_DMA_HANDLER__NONE 0 - /* DMA Channel Mappings */ // D(DMAx, Stream) // at32f43x has DMAMUX that allow arbitrary assignment of peripherals to streams. diff --git a/src/platform/AT32/usbd_msc_mem.h b/src/platform/AT32/usbd_msc_mem.h index 928a2a8b6..82685ea1a 100644 --- a/src/platform/AT32/usbd_msc_mem.h +++ b/src/platform/AT32/usbd_msc_mem.h @@ -37,7 +37,6 @@ * @} */ - /** @defgroup USBD_MEM_Exported_TypesDefinitions * @{ */ diff --git a/src/platform/SITL/sitl.c b/src/platform/SITL/sitl.c index da8cfd368..73abf4a9c 100644 --- a/src/platform/SITL/sitl.c +++ b/src/platform/SITL/sitl.c @@ -183,7 +183,6 @@ void updateState(const fdm_packet* pkt) imuUpdateAttitude(micros()); #endif - if (deltaSim < 0.02 && deltaSim > 0) { // simulator should run faster than 50Hz // simRate = simRate * 0.5 + (1e6 * deltaSim / (realtime_now - last_realtime)) * 0.5; struct timespec out_ts; @@ -501,7 +500,6 @@ int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y) return x->tv_sec < y->tv_sec; } - // PWM part pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS]; static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS]; diff --git a/src/platform/SITL/target/SITL/target.h b/src/platform/SITL/target/SITL/target.h index 68124c045..e620fa9a4 100644 --- a/src/platform/SITL/target/SITL/target.h +++ b/src/platform/SITL/target/SITL/target.h @@ -145,7 +145,6 @@ #define TARGET_FLASH_SIZE 2048 - #define DEFIO_NO_PORTS // suppress 'no pins defined' warning #define FLASH_PAGE_SIZE (0x400) diff --git a/src/platform/STM32/adc_stm32f7xx.c b/src/platform/STM32/adc_stm32f7xx.c index 0170831fd..b26e0295b 100644 --- a/src/platform/STM32/adc_stm32f7xx.c +++ b/src/platform/STM32/adc_stm32f7xx.c @@ -316,7 +316,6 @@ void adcInit(const adcConfig_t *config) adc.DmaHandle.Init.MemBurst = DMA_MBURST_SINGLE; adc.DmaHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; - if (HAL_DMA_Init(&adc.DmaHandle) != HAL_OK) { /* Initialization Error */ diff --git a/src/platform/STM32/bus_octospi_stm32h7xx.c b/src/platform/STM32/bus_octospi_stm32h7xx.c index f45aaddb4..484283f45 100644 --- a/src/platform/STM32/bus_octospi_stm32h7xx.c +++ b/src/platform/STM32/bus_octospi_stm32h7xx.c @@ -119,7 +119,6 @@ MMFLASH_CODE_NOINLINE static void Error_Handler(void) { } } - #define __OSPI_GET_FLAG(__INSTANCE__, __FLAG__) ((READ_BIT((__INSTANCE__)->SR, (__FLAG__)) != 0U) ? SET : RESET) #define __OSPI_CLEAR_FLAG(__INSTANCE__, __FLAG__) WRITE_REG((__INSTANCE__)->FCR, (__FLAG__)) #define __OSPI_ENABLE(__INSTANCE__) SET_BIT((__INSTANCE__)->CR, OCTOSPI_CR_EN) @@ -147,7 +146,6 @@ MMFLASH_CODE_NOINLINE static void octoSpiWaitStatusFlags(OCTOSPI_TypeDef *instan } } - typedef struct { uint32_t OperationType; @@ -206,7 +204,6 @@ MMFLASH_CODE_NOINLINE static ErrorStatus octoSpiConfigureCommand(OCTOSPI_TypeDef } } - if (cmd->InstructionMode != OSPI_INSTRUCTION_NONE) { if (cmd->AddressMode != OSPI_ADDRESS_NONE) @@ -334,7 +331,6 @@ MMFLASH_CODE_NOINLINE ErrorStatus octoSpiTransmit(OCTOSPI_TypeDef *instance, uin return ERROR; } - __IO uint32_t XferCount = READ_REG(instance->DLR) + 1U; uint8_t *pBuffPtr = data; @@ -542,7 +538,6 @@ MMFLASH_CODE static uint32_t octoSpi_addressSizeFromValue(uint8_t addressSize) return octoSpi_addressSizeMap[((addressSize + 1) / 8) - 1]; // rounds to nearest OSPI_ADDRESS_* value that will hold the address. } - MMFLASH_CODE_NOINLINE bool octoSpiTransmit1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length) { OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. @@ -792,7 +787,6 @@ MMFLASH_CODE_NOINLINE bool octoSpiTransmitWithAddress4LINES(OCTOSPI_TypeDef *ins status = octoSpiTransmit(instance, (uint8_t *)out); } - return status == SUCCESS; } @@ -828,7 +822,6 @@ MMFLASH_CODE_NOINLINE bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *i return status == SUCCESS; } - void octoSpiInitDevice(OCTOSPIDevice device) { octoSpiDevice_t *octoSpi = &(octoSpiDevice[device]); diff --git a/src/platform/STM32/bus_quadspi_hal.c b/src/platform/STM32/bus_quadspi_hal.c index f3d91a42f..5c93f1f3a 100644 --- a/src/platform/STM32/bus_quadspi_hal.c +++ b/src/platform/STM32/bus_quadspi_hal.c @@ -203,14 +203,11 @@ void quadSpiDeselectDevice(QUADSPI_TypeDef *instance) } } - - bool quadSpiTransmit1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length) { QUADSPIDevice device = quadSpiDeviceByInstance(instance); HAL_StatusTypeDef status; - QSPI_CommandTypeDef cmd; cmd.InstructionMode = QSPI_INSTRUCTION_1_LINE; cmd.AddressMode = QSPI_ADDRESS_NONE; @@ -364,7 +361,6 @@ bool quadSpiReceiveWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instructi return true; } - bool quadSpiReceiveWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length) { QUADSPIDevice device = quadSpiDeviceByInstance(instance); @@ -515,7 +511,6 @@ bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instr return false; } - return true; } diff --git a/src/platform/STM32/bus_spi_ll.c b/src/platform/STM32/bus_spi_ll.c index 75615174f..da00e15d3 100644 --- a/src/platform/STM32/bus_spi_ll.c +++ b/src/platform/STM32/bus_spi_ll.c @@ -203,7 +203,6 @@ void spiInternalResetStream(dmaChannelDescriptor_t *descriptor) DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); } - FAST_CODE static bool spiInternalReadWriteBufPolled(SPI_TypeDef *instance, const uint8_t *txData, uint8_t *rxData, int len) { #if defined(STM32H7) diff --git a/src/platform/STM32/bus_spi_stdperiph.c b/src/platform/STM32/bus_spi_stdperiph.c index 988fc7987..04a8e63af 100644 --- a/src/platform/STM32/bus_spi_stdperiph.c +++ b/src/platform/STM32/bus_spi_stdperiph.c @@ -76,7 +76,6 @@ static void spiSetDivisorBRreg(SPI_TypeDef *instance, uint16_t divisor) #undef BR_BITS } - void spiInitDevice(SPIDevice device) { spiDevice_t *spi = &(spiDevice[device]); @@ -287,7 +286,6 @@ void spiInternalStartDMA(const extDevice_t *dev) } } - void spiInternalStopDMA (const extDevice_t *dev) { dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx; diff --git a/src/platform/STM32/dshot_bitbang.c b/src/platform/STM32/dshot_bitbang.c index 6b4b16511..b6d98d3fc 100644 --- a/src/platform/STM32/dshot_bitbang.c +++ b/src/platform/STM32/dshot_bitbang.c @@ -97,7 +97,6 @@ BB_INPUT_BUFFER_ATTRIBUTE uint16_t bbInputBuffer[DSHOT_BB_PORT_IP_BUF_CACHE_ALIG uint8_t bbPuPdMode; FAST_DATA_ZERO_INIT timeUs_t dshotFrameUs; - const timerHardware_t bbTimerHardware[] = { #if defined(STM32F4) || defined(STM32F7) #if !defined(STM32F411xE) @@ -719,7 +718,6 @@ static void bbPostInit(void) return; } - bbMotors[motorIndex].enabled = true; // Fill in motors structure for 4way access (XXX Should be refactored) diff --git a/src/platform/STM32/exti.c b/src/platform/STM32/exti.c index 1ddf71b1a..bc9c6c464 100644 --- a/src/platform/STM32/exti.c +++ b/src/platform/STM32/exti.c @@ -193,7 +193,6 @@ void EXTIEnable(IO_t io) #endif } - void EXTIDisable(IO_t io) { #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) @@ -233,7 +232,6 @@ void EXTI_IRQHandler(uint32_t mask) struct dummy \ /**/ - _EXTI_IRQ_HANDLER(EXTI0_IRQHandler, 0x0001); _EXTI_IRQ_HANDLER(EXTI1_IRQHandler, 0x0002); #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) diff --git a/src/platform/STM32/pwm_output_dshot.c b/src/platform/STM32/pwm_output_dshot.c index d162d5859..033a10907 100644 --- a/src/platform/STM32/pwm_output_dshot.c +++ b/src/platform/STM32/pwm_output_dshot.c @@ -108,7 +108,6 @@ FAST_CODE void pwmDshotSetDirectionOutput( xDMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE); } - #ifdef USE_DSHOT_TELEMETRY FAST_CODE static void pwmDshotSetDirectionInput( @@ -141,7 +140,6 @@ static void pwmDshotSetDirectionInput( } #endif - void pwmCompleteDshotMotorUpdate(void) { /* If there is a dshot command loaded up, time it correctly with motor update*/ @@ -330,7 +328,6 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m motor->icInitStruct.TIM_ICFilter = 2; #endif - #ifdef USE_DSHOT_DMAR if (useBurstDshot) { motor->timer->dmaBurstRef = dmaRef; diff --git a/src/platform/STM32/pwm_output_dshot_hal.c b/src/platform/STM32/pwm_output_dshot_hal.c index 15b000ed8..15d5a31fe 100644 --- a/src/platform/STM32/pwm_output_dshot_hal.c +++ b/src/platform/STM32/pwm_output_dshot_hal.c @@ -135,7 +135,6 @@ FAST_CODE static void pwmDshotSetDirectionInput( } #endif - FAST_CODE void pwmCompleteDshotMotorUpdate(void) { /* If there is a dshot command loaded up, time it correctly with motor update*/ diff --git a/src/platform/STM32/sdio_f4xx.c b/src/platform/STM32/sdio_f4xx.c index 08ed8b09f..6f9b7cd1f 100644 --- a/src/platform/STM32/sdio_f4xx.c +++ b/src/platform/STM32/sdio_f4xx.c @@ -50,7 +50,6 @@ #include "build/debug.h" - /* Define(s) --------------------------------------------------------------------------------------------------------*/ #define DMA_CHANNEL_4 ((uint32_t)0x08000000) @@ -124,8 +123,6 @@ #define SD_SDIO_SEND_IF_COND ((uint32_t)SD_CMD_HS_SEND_EXT_CSD) - - #define SD_BUS_WIDE_1B ((uint32_t)0x00000000) #define SD_BUS_WIDE_4B SDIO_CLKCR_WIDBUS_0 #define SD_BUS_WIDE_8B SDIO_CLKCR_WIDBUS_1 @@ -151,7 +148,6 @@ #define SDIO_INIT_CLK_DIV ((uint8_t)0x76) #define SDIO_CLK_DIV ((uint8_t)0x00) - #define SD_CMD_GO_IDLE_STATE ((uint8_t)0) // Resets the SD memory card. #define SD_CMD_SEND_OP_COND ((uint8_t)1) // Sends host capacity support information and activates the card's initialization process. #define SD_CMD_ALL_SEND_CID ((uint8_t)2) // Asks any card connected to the host to send the CID numbers on the CMD line. @@ -196,7 +192,6 @@ #define SDIO_DMA_ST3 1 - /* Typedef(s) -------------------------------------------------------------------------------------------------------*/ typedef enum @@ -205,7 +200,6 @@ typedef enum SD_MULTIPLE_BLOCK = 1, // Multiple blocks operation } SD_Operation_t; - typedef struct { uint32_t CSD[4]; // SD card specific data table @@ -240,7 +234,6 @@ SD_CardType_t SD_CardType; static volatile uint32_t TimeOut; DMA_Stream_TypeDef *dmaStream; - /* Private function(s) ----------------------------------------------------------------------------------------------*/ static void SD_DataTransferInit (uint32_t Size, uint32_t DataBlockSize, bool IsItReadFromCard); @@ -278,7 +271,6 @@ static void SD_DataTransferInit(uint32_t Size, uint32_t DataBlockSize, bool IsIt return; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** SD_TransmitCommand * @@ -302,7 +294,6 @@ static SD_Error_t SD_TransmitCommand(uint32_t Command, uint32_t Argument, int8_t return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Checks for error conditions for any response. @@ -389,7 +380,6 @@ static SD_Error_t SD_CmdResponse(uint8_t SD_CMD, int8_t ResponseType) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Analyze the OCR response and return the appropriate error code @@ -422,7 +412,6 @@ static SD_Error_t CheckOCR_Response(uint32_t Response_R1) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** GetResponse * @@ -437,7 +426,6 @@ static void SD_GetResponse(uint32_t* pResponse) pResponse[3] = SDIO->RESP4; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief SD DMA transfer complete RX and TX callback. @@ -469,7 +457,6 @@ static void SD_DMA_Complete(DMA_Stream_TypeDef* pDMA_Stream) } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Initializes all cards or single card as the case may be Card(s) come @@ -523,7 +510,6 @@ static SD_Error_t SD_InitializeCard(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Prepre the DMA transfer @@ -578,7 +564,6 @@ static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32 } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Reads block(s) from a specified address in a card. The Data transfer @@ -634,7 +619,6 @@ SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t Bl return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Writes block(s) to a specified address in a card. The Data transfer @@ -835,7 +819,6 @@ SD_Error_t SD_Erase(uint64_t StartAddress, uint64_t EndAddress) } */ - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Returns information about specific card. @@ -1045,7 +1028,6 @@ SD_Error_t SD_GetCardInfo(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Enables wide bus operation for the requested card if supported by @@ -1122,11 +1104,9 @@ static SD_Error_t SD_WideBusOperationConfig(uint32_t WideMode) ErrorState = SD_UNSUPPORTED_FEATURE; } - return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Switches the SD card to High Speed mode. @@ -1207,7 +1187,6 @@ SD_Error_t SD_HighSpeed(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Gets the current card's data status. @@ -1219,7 +1198,6 @@ SD_Error_t SD_GetStatus(void) uint32_t Response1; SD_CardState_t CardState; - // Send Status command if((ErrorState = SD_TransmitCommand((SD_CMD_SEND_STATUS | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1)) == SD_OK) { @@ -1239,7 +1217,6 @@ SD_Error_t SD_GetStatus(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Gets the SD card status. @@ -1372,7 +1349,6 @@ SD_Error_t SD_GetCardStatus(SD_CardStatus_t* pCardStatus) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Enquires cards about their operating voltage and configures clock @@ -1463,7 +1439,6 @@ static SD_Error_t SD_PowerON(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Turns the SDIO output signals off. @@ -1477,7 +1452,6 @@ static void SD_PowerOFF(void) } #endif - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Finds the SD card SCR register value. @@ -1531,7 +1505,6 @@ static SD_Error_t SD_FindSCR(uint32_t *pSCR) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Checks if the SD card is in programming state. @@ -1645,7 +1618,6 @@ bool SD_Initialize_LL(DMA_Stream_TypeDef *dma) return true; } - /** -----------------------------------------------------------------------------------------------------------------*/ bool SD_GetState(void) { @@ -1654,7 +1626,6 @@ bool SD_GetState(void) return false; } - /** -----------------------------------------------------------------------------------------------------------------*/ static SD_Error_t SD_DoInit(void) { @@ -1849,7 +1820,6 @@ void SDIO_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma) } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief This function handles DMA2 Stream 6 interrupt request. diff --git a/src/platform/STM32/sdio_f7xx.c b/src/platform/STM32/sdio_f7xx.c index 6affadaa2..d3edd83df 100644 --- a/src/platform/STM32/sdio_f7xx.c +++ b/src/platform/STM32/sdio_f7xx.c @@ -106,8 +106,6 @@ #define SD_SDMMC_SEND_IF_COND ((uint32_t)SD_CMD_HS_SEND_EXT_CSD) - - #define SD_BUS_WIDE_1B ((uint32_t)0x00000000) #define SD_BUS_WIDE_4B SDMMC_CLKCR_WIDBUS_0 #define SD_BUS_WIDE_8B SDMMC_CLKCR_WIDBUS_1 @@ -133,7 +131,6 @@ #define SDMMC_INIT_CLK_DIV ((uint8_t)0x76) #define SDMMC_CLK_DIV ((uint8_t)0x00) - #define SD_CMD_GO_IDLE_STATE ((uint8_t)0) // Resets the SD memory card. #define SD_CMD_SEND_OP_COND ((uint8_t)1) // Sends host capacity support information and activates the card's initialization process. #define SD_CMD_ALL_SEND_CID ((uint8_t)2) // Asks any card connected to the host to send the CID numbers on the CMD line. @@ -178,7 +175,6 @@ #define SDMMC_DMA_ST3 1 - /* Typedef(s) -------------------------------------------------------------------------------------------------------*/ typedef enum @@ -187,7 +183,6 @@ typedef enum SD_MULTIPLE_BLOCK = 1, // Multiple blocks operation } SD_Operation_t; - typedef struct { uint32_t CSD[4]; // SD card specific data table @@ -222,7 +217,6 @@ SD_CardType_t SD_CardType; static volatile uint32_t TimeOut; DMA_Stream_TypeDef *dmaStream; - /* Private function(s) ----------------------------------------------------------------------------------------------*/ static void SD_DataTransferInit (uint32_t Size, uint32_t DataBlockSize, bool IsItReadFromCard); @@ -260,7 +254,6 @@ static void SD_DataTransferInit(uint32_t Size, uint32_t DataBlockSize, bool IsIt return; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** SD_TransmitCommand * @@ -284,7 +277,6 @@ static SD_Error_t SD_TransmitCommand(uint32_t Command, uint32_t Argument, int8_t return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Checks for error conditions for any response. @@ -371,7 +363,6 @@ static SD_Error_t SD_CmdResponse(uint8_t SD_CMD, int8_t ResponseType) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Analyze the OCR response and return the appropriate error code @@ -404,7 +395,6 @@ static SD_Error_t CheckOCR_Response(uint32_t Response_R1) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** GetResponse * @@ -419,7 +409,6 @@ static void SD_GetResponse(uint32_t* pResponse) pResponse[3] = SDMMC1->RESP4; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief SD DMA transfer complete RX and TX callback. @@ -451,7 +440,6 @@ static void SD_DMA_Complete(DMA_Stream_TypeDef* pDMA_Stream) } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Initializes all cards or single card as the case may be Card(s) come @@ -505,7 +493,6 @@ static SD_Error_t SD_InitializeCard(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Prepre the DMA transfer @@ -560,7 +547,6 @@ static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32 } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Reads block(s) from a specified address in a card. The Data transfer @@ -616,7 +602,6 @@ SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t Bl return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Writes block(s) to a specified address in a card. The Data transfer @@ -817,7 +802,6 @@ SD_Error_t SD_Erase(uint64_t StartAddress, uint64_t EndAddress) } */ - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Returns information about specific card. @@ -1027,7 +1011,6 @@ SD_Error_t SD_GetCardInfo(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Enables wide bus operation for the requested card if supported by @@ -1104,11 +1087,9 @@ static SD_Error_t SD_WideBusOperationConfig(uint32_t WideMode) ErrorState = SD_UNSUPPORTED_FEATURE; } - return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Switches the SD card to High Speed mode. @@ -1192,7 +1173,6 @@ SD_Error_t HAL_SD_HighSpeed(void) */ - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Gets the current card's data status. @@ -1204,7 +1184,6 @@ SD_Error_t SD_GetStatus(void) uint32_t Response1; SD_CardState_t CardState; - // Send Status command if((ErrorState = SD_TransmitCommand((SD_CMD_SEND_STATUS | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1)) == SD_OK) { @@ -1224,7 +1203,6 @@ SD_Error_t SD_GetStatus(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Gets the SD card status. @@ -1357,7 +1335,6 @@ SD_Error_t SD_GetCardStatus(SD_CardStatus_t* pCardStatus) return SD_OK; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Enquires cards about their operating voltage and configures clock @@ -1448,7 +1425,6 @@ static SD_Error_t SD_PowerON(void) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Turns the SDMMC1 output signals off. @@ -1462,7 +1438,6 @@ static void SD_PowerOFF(void) } #endif - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Finds the SD card SCR register value. @@ -1516,7 +1491,6 @@ static SD_Error_t SD_FindSCR(uint32_t *pSCR) return ErrorState; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief Checks if the SD card is in programming state. @@ -1629,7 +1603,6 @@ bool SD_Initialize_LL(DMA_Stream_TypeDef *dma) return true; } - /** -----------------------------------------------------------------------------------------------------------------*/ bool SD_GetState(void) { @@ -1638,7 +1611,6 @@ bool SD_GetState(void) return false; } - /** -----------------------------------------------------------------------------------------------------------------*/ static SD_Error_t SD_DoInit(void) { @@ -1702,7 +1674,6 @@ SD_Error_t SD_Init(void) return result; } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief This function handles SD card interrupt request. @@ -1830,7 +1801,6 @@ void SDMMC_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma) } } - /** -----------------------------------------------------------------------------------------------------------------*/ /** * @brief This function handles DMA2 Stream 6 interrupt request. diff --git a/src/platform/STM32/serial_uart_hal.c b/src/platform/STM32/serial_uart_hal.c index 3b0bf2267..f319bce78 100644 --- a/src/platform/STM32/serial_uart_hal.c +++ b/src/platform/STM32/serial_uart_hal.c @@ -103,7 +103,6 @@ void uartReconfigure(uartPort_t *uartPort) if (uartPort->port.mode & MODE_TX) uartPort->Handle.Init.Mode |= UART_MODE_TX; - usartConfigurePinInversion(uartPort); #if !(defined(STM32F1) || defined(STM32F4)) uartConfigurePinSwap(uartPort); @@ -146,7 +145,6 @@ void uartReconfigure(uartPort_t *uartPort) #endif uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - HAL_DMA_DeInit(&uartPort->rxDMAHandle); HAL_DMA_Init(&uartPort->rxDMAHandle); /* Associate the initialized DMA handle to the UART handle */ @@ -197,7 +195,6 @@ void uartReconfigure(uartPort_t *uartPort) #endif uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - HAL_DMA_DeInit(&uartPort->txDMAHandle); HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle); if (status != HAL_OK) diff --git a/src/platform/STM32/serial_usb_vcp.c b/src/platform/STM32/serial_usb_vcp.c index 4e1e83d32..27fa8223b 100644 --- a/src/platform/STM32/serial_usb_vcp.c +++ b/src/platform/STM32/serial_usb_vcp.c @@ -60,7 +60,6 @@ USBD_HandleTypeDef USBD_Device; #include "drivers/serial.h" #include "drivers/serial_usb_vcp.h" - #define USB_TIMEOUT 50 static vcpPort_t vcpPort = {0}; @@ -265,7 +264,6 @@ serialPort_t *usbVcpOpen(void) delay(100); // Cold boot failures observed without this, even when USB cable is not connected #endif - #else Set_System(); Set_USBClock(); diff --git a/src/platform/STM32/startup/stm32f4xx_hal_conf.h b/src/platform/STM32/startup/stm32f4xx_hal_conf.h index 3d4a9c026..83b0a54b8 100644 --- a/src/platform/STM32/startup/stm32f4xx_hal_conf.h +++ b/src/platform/STM32/startup/stm32f4xx_hal_conf.h @@ -438,12 +438,10 @@ #define assert_param(expr) ((void)0) #endif /* USE_FULL_ASSERT */ - #ifdef __cplusplus } #endif #endif /* __STM32F4xx_HAL_CONF_H */ - /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/platform/STM32/startup/stm32f7xx_hal_conf.h b/src/platform/STM32/startup/stm32f7xx_hal_conf.h index c6c2504d9..4164d0799 100644 --- a/src/platform/STM32/startup/stm32f7xx_hal_conf.h +++ b/src/platform/STM32/startup/stm32f7xx_hal_conf.h @@ -454,5 +454,4 @@ #endif /* __STM32F7xx_HAL_CONF_H */ - /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/platform/STM32/startup/stm32g4xx_hal_conf.h b/src/platform/STM32/startup/stm32g4xx_hal_conf.h index 2a89d187e..3fee2914f 100644 --- a/src/platform/STM32/startup/stm32g4xx_hal_conf.h +++ b/src/platform/STM32/startup/stm32g4xx_hal_conf.h @@ -378,5 +378,4 @@ void assert_failed(uint8_t *file, uint32_t line); #endif /* STM32G4xx_HAL_CONF_H */ - /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/platform/STM32/startup/stm32h5xx_hal_conf.h b/src/platform/STM32/startup/stm32h5xx_hal_conf.h index 2094bc621..1edd33ce1 100644 --- a/src/platform/STM32/startup/stm32h5xx_hal_conf.h +++ b/src/platform/STM32/startup/stm32h5xx_hal_conf.h @@ -157,7 +157,6 @@ in voltage and temperature.*/ #define LSE_STARTUP_TIMEOUT 5000UL /*!< Time out for LSE start up, in ms */ #endif /* LSE_STARTUP_TIMEOUT */ - /** * @brief External clock source for SPI/SAI peripheral * This value is used by the SPI/SAI HAL module to compute the SPI/SAI clock source @@ -246,7 +245,6 @@ in voltage and temperature.*/ */ #define USE_SPI_CRC 1U - /* Includes ----------------------------------------------------------------------------------------------------------*/ /** * @brief Include module's header file diff --git a/src/platform/STM32/startup/stm32h7xx_hal_conf.h b/src/platform/STM32/startup/stm32h7xx_hal_conf.h index 4cd8d653e..21ce446ca 100644 --- a/src/platform/STM32/startup/stm32h7xx_hal_conf.h +++ b/src/platform/STM32/startup/stm32h7xx_hal_conf.h @@ -152,7 +152,6 @@ #define LSE_VALUE (32768UL) /*!< Value of the External oscillator in Hz*/ #endif /* LSE_VALUE */ - #if !defined (LSE_STARTUP_TIMEOUT) #define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */ #endif /* LSE_STARTUP_TIMEOUT */ @@ -252,8 +251,6 @@ */ /* #define USE_FULL_ASSERT 1 */ - - /* Includes ------------------------------------------------------------------*/ /** * @brief Include module's header file @@ -526,5 +523,4 @@ #endif /* __STM32H7xx_HAL_CONF_H */ - /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/platform/STM32/startup/system_stm32f4xx.c b/src/platform/STM32/startup/system_stm32f4xx.c index d03646476..dc8306d00 100644 --- a/src/platform/STM32/startup/system_stm32f4xx.c +++ b/src/platform/STM32/startup/system_stm32f4xx.c @@ -321,7 +321,6 @@ #include "platform.h" #include "drivers/persistent.h" - /** * @} */ @@ -1228,7 +1227,6 @@ void SystemInit_ExtMemCtl(void) } #endif /* DATA_IN_ExtSDRAM */ - /** * @} */ diff --git a/src/platform/STM32/startup/system_stm32g4xx.h b/src/platform/STM32/startup/system_stm32g4xx.h index 587324f6b..cd4b1278c 100644 --- a/src/platform/STM32/startup/system_stm32g4xx.h +++ b/src/platform/STM32/startup/system_stm32g4xx.h @@ -38,7 +38,6 @@ * @} */ - /** @addtogroup STM32G4xx_System_Exported_Variables * @{ */ diff --git a/src/platform/STM32/startup/system_stm32h5xx.c b/src/platform/STM32/startup/system_stm32h5xx.c index 23e7af686..5e7ec5900 100644 --- a/src/platform/STM32/startup/system_stm32h5xx.c +++ b/src/platform/STM32/startup/system_stm32h5xx.c @@ -391,7 +391,6 @@ void SystemCoreClockUpdate(void) SystemCoreClock >>= tmp; } - /** * @} */ diff --git a/src/platform/STM32/startup/system_stm32h5xx.h b/src/platform/STM32/startup/system_stm32h5xx.h index a7a5a751f..f641468e0 100644 --- a/src/platform/STM32/startup/system_stm32h5xx.h +++ b/src/platform/STM32/startup/system_stm32h5xx.h @@ -59,7 +59,6 @@ extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ * @} */ - /** @addtogroup STM32H5xx_System_Exported_Functions * @{ */ @@ -71,7 +70,6 @@ extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ */ extern void SystemInit (void); - /** * @brief Update SystemCoreClock variable. * @@ -79,7 +77,6 @@ extern void SystemInit (void); */ extern void SystemCoreClockUpdate (void); - /** * @brief Update SystemCoreClock variable from secure application and return its value * when security is implemented in the system (Non-secure callable function). diff --git a/src/platform/STM32/startup/system_stm32h7xx.c b/src/platform/STM32/startup/system_stm32h7xx.c index ad6b563f1..75776aa8a 100644 --- a/src/platform/STM32/startup/system_stm32h7xx.c +++ b/src/platform/STM32/startup/system_stm32h7xx.c @@ -76,10 +76,8 @@ #include "drivers/memprot.h" #include "drivers/system.h" - #define HSI_FREQ ((uint32_t)64000000) // Frequency of HSI is 64Mhz on all H7 variants. - // If `HSE_VALUE` isn't specified, use HSI. This allows HSI to be selected as the PLL source // later in this file, and adjusts PLL scalers to use the HSI's frequency as the timing source. #if !defined (HSE_VALUE) @@ -425,7 +423,6 @@ static void SystemClockHSE_Config(void) // Use of PLL2 and PLL3 are not determined yet. // A review of total system wide clock requirements is necessary. - // Configure SCGU (System Clock Generation Unit) // Select PLL as system clock source and configure bus clock dividers. // @@ -1052,7 +1049,6 @@ void SystemInit_ExtMemCtl(void) /*FMC controller Enable*/ FMC_Bank1->BTCR[0] |= 0x80000000; - #endif /* DATA_IN_ExtSDRAM */ #if defined(DATA_IN_ExtSRAM) @@ -1124,7 +1120,6 @@ void SystemInit_ExtMemCtl(void) } #endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */ - /** * @} */ diff --git a/src/platform/STM32/startup/system_stm32h7xx.h b/src/platform/STM32/startup/system_stm32h7xx.h index c22d942c3..62ad22fd5 100644 --- a/src/platform/STM32/startup/system_stm32h7xx.h +++ b/src/platform/STM32/startup/system_stm32h7xx.h @@ -59,7 +59,6 @@ * @} */ - /** @addtogroup STM32H7xx_System_Exported_types * @{ */ diff --git a/src/platform/STM32/system_stm32f4xx.c b/src/platform/STM32/system_stm32f4xx.c index 60e8acb0e..536080775 100644 --- a/src/platform/STM32/system_stm32f4xx.c +++ b/src/platform/STM32/system_stm32f4xx.c @@ -29,7 +29,6 @@ #include "drivers/system.h" #include "drivers/persistent.h" - #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) void SetSysClock(void); diff --git a/src/platform/STM32/system_stm32f7xx.c b/src/platform/STM32/system_stm32f7xx.c index 0b377c1b9..8f6da10c7 100644 --- a/src/platform/STM32/system_stm32f7xx.c +++ b/src/platform/STM32/system_stm32f7xx.c @@ -33,7 +33,6 @@ #include "stm32f7xx_ll_cortex.h" - #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) #define DEFAULT_STACK_POINTER ((uint32_t *) 0x1FF00000) diff --git a/src/platform/STM32/system_stm32g4xx.c b/src/platform/STM32/system_stm32g4xx.c index b2e067947..313ff9dcd 100644 --- a/src/platform/STM32/system_stm32g4xx.c +++ b/src/platform/STM32/system_stm32g4xx.c @@ -138,7 +138,6 @@ void systemJumpToBootloader(void) while (1); } - void systemProcessResetReason(void) { uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); diff --git a/src/platform/STM32/system_stm32h7xx.c b/src/platform/STM32/system_stm32h7xx.c index 8f4f8ce79..29ae3bef7 100644 --- a/src/platform/STM32/system_stm32h7xx.c +++ b/src/platform/STM32/system_stm32h7xx.c @@ -28,7 +28,6 @@ #include "drivers/persistent.h" #include "drivers/system.h" - void SystemClock_Config(void); void configureMasterClockOutputs(void) @@ -171,7 +170,6 @@ void systemResetToBootloader(bootloaderRequestType_e requestType) NVIC_SystemReset(); } - #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1ff09800) #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) @@ -197,7 +195,6 @@ void systemJumpToBootloader(void) while (1); } - void systemProcessResetReason(void) { uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); diff --git a/src/platform/STM32/target/STM32H563/target.h b/src/platform/STM32/target/STM32H563/target.h index 5af44b396..cdf17a3ed 100644 --- a/src/platform/STM32/target/STM32H563/target.h +++ b/src/platform/STM32/target/STM32H563/target.h @@ -79,8 +79,6 @@ #define USE_VIRTUAL_GYRO - - //#define USE_I2C_DEVICE_1 //#define USE_I2C_DEVICE_2 //#define USE_I2C_DEVICE_3 diff --git a/src/platform/STM32/target/STM32H725/target.h b/src/platform/STM32/target/STM32H725/target.h index 394c299a5..a7dad159b 100644 --- a/src/platform/STM32/target/STM32H725/target.h +++ b/src/platform/STM32/target/STM32H725/target.h @@ -78,7 +78,6 @@ #define USE_SDCARD_SDIO #endif - #define USE_VCP #define USE_USB_DETECT diff --git a/src/platform/STM32/timer_def.h b/src/platform/STM32/timer_def.h index 3c3bce48e..c8aae1f12 100644 --- a/src/platform/STM32/timer_def.h +++ b/src/platform/STM32/timer_def.h @@ -184,7 +184,6 @@ #define DEF_TIM_DMA_HANDLER__D(dma_n, stream_n, chan_n) DMA ## dma_n ## _ST ## stream_n ## _HANDLER #define DEF_TIM_DMA_HANDLER__NONE 0 - /* F4 Stream Mappings */ // D(DMAx, Stream, Channel) #define DEF_TIM_DMA__BTCH_TIM1_CH1 D(2, 6, 0),D(2, 1, 6),D(2, 3, 6) diff --git a/src/platform/STM32/timer_stm32f4xx.c b/src/platform/STM32/timer_stm32f4xx.c index bd1218c4d..4bc5b1d2d 100644 --- a/src/platform/STM32/timer_stm32f4xx.c +++ b/src/platform/STM32/timer_stm32f4xx.c @@ -32,7 +32,6 @@ #include "drivers/rcc.h" #include "drivers/timer.h" - const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn}, { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn}, @@ -187,7 +186,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { }; #endif - /* need a mapping from dma and timers to pins, and the values should all be set here to the dmaMotors array. this mapping could be used for both these motors and for led strip. diff --git a/src/platform/STM32/timer_stm32f7xx.c b/src/platform/STM32/timer_stm32f7xx.c index 43830c6aa..464873c89 100644 --- a/src/platform/STM32/timer_stm32f7xx.c +++ b/src/platform/STM32/timer_stm32f7xx.c @@ -166,7 +166,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { }; #endif - /* need a mapping from dma and timers to pins, and the values should all be set here to the dmaMotors array. this mapping could be used for both these motors and for led strip. diff --git a/src/platform/STM32/timer_stm32g4xx.c b/src/platform/STM32/timer_stm32g4xx.c index d6826cb96..e93f79fbe 100644 --- a/src/platform/STM32/timer_stm32g4xx.c +++ b/src/platform/STM32/timer_stm32g4xx.c @@ -32,7 +32,6 @@ #include "drivers/rcc.h" #include "drivers/timer.h" - const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn}, { .TIMx = TIM2, .rcc = RCC_APB11(TIM2), .inputIrq = TIM2_IRQn}, diff --git a/src/platform/STM32/timer_stm32h7xx.c b/src/platform/STM32/timer_stm32h7xx.c index e4119a109..78e066ca8 100644 --- a/src/platform/STM32/timer_stm32h7xx.c +++ b/src/platform/STM32/timer_stm32h7xx.c @@ -160,7 +160,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { }; #endif - uint32_t timerClock(const TIM_TypeDef *tim) { int timpre; diff --git a/src/platform/STM32/transponder_ir_io_hal.c b/src/platform/STM32/transponder_ir_io_hal.c index 8fa20459a..1f3f20340 100644 --- a/src/platform/STM32/transponder_ir_io_hal.c +++ b/src/platform/STM32/transponder_ir_io_hal.c @@ -163,7 +163,6 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder) return; } - RCC_ClockCmd(timerRCC(timer), ENABLE); /* PWM1 Mode configuration: Channel1 */ @@ -275,7 +274,6 @@ void transponderIrDisable(void) HAL_TIM_PWM_Stop(&TimHandle, timerChannel); } - IOInit(transponderIO, OWNER_TRANSPONDER, 0); #ifdef TRANSPONDER_INVERTED diff --git a/src/platform/STM32/usbd_msc_desc.c b/src/platform/STM32/usbd_msc_desc.c index ebff704b2..c95ce0c70 100644 --- a/src/platform/STM32/usbd_msc_desc.c +++ b/src/platform/STM32/usbd_msc_desc.c @@ -48,7 +48,6 @@ * @{ */ - /** @defgroup USBD_DESC * @brief USBD descriptors module * @{ @@ -61,7 +60,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Defines * @{ */ @@ -81,7 +79,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Macros * @{ */ @@ -89,7 +86,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Variables * @{ */ @@ -184,7 +180,6 @@ __ALIGN_BEGIN uint8_t USBD_StrDesc_MSC[USB_MAX_STR_DESC_SIZ] __ALIGN_END ; * @} */ - /** @defgroup USBD_DESC_Private_FunctionPrototypes * @{ */ @@ -194,7 +189,6 @@ static void Get_SerialNum(void); * @} */ - /** @defgroup USBD_DESC_Private_Functions * @{ */ @@ -227,7 +221,6 @@ uint8_t * USBD_MSC_LangIDStrDescriptor( uint8_t speed , uint16_t *length) return (uint8_t*)USBD_LangIDDesc_MSC; } - /** * @brief USBD_USR_ProductStrDescriptor * return the product string descriptor @@ -300,7 +293,6 @@ uint8_t * USBD_MSC_ConfigStrDescriptor( uint8_t speed , uint16_t *length) return USBD_StrDesc_MSC; } - /** * @brief USBD_USR_InterfaceStrDescriptor * return the interface string descriptor @@ -371,17 +363,14 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len) } } - /** * @} */ - /** * @} */ - /** * @} */ diff --git a/src/platform/STM32/usbd_msc_desc.h b/src/platform/STM32/usbd_msc_desc.h index 03a3d9bbc..6a20f504c 100644 --- a/src/platform/STM32/usbd_msc_desc.h +++ b/src/platform/STM32/usbd_msc_desc.h @@ -69,7 +69,6 @@ * @} */ - /** @defgroup USBD_DESC_Exported_TypesDefinitions * @{ */ @@ -77,8 +76,6 @@ * @} */ - - /** @defgroup USBD_DESC_Exported_Macros * @{ */ @@ -103,7 +100,6 @@ extern USBD_DEVICE USR_desc; * @{ */ - uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length); diff --git a/src/platform/STM32/vcp/hw_config.c b/src/platform/STM32/vcp/hw_config.c index 43fbc5892..f5af1b2fa 100644 --- a/src/platform/STM32/vcp/hw_config.c +++ b/src/platform/STM32/vcp/hw_config.c @@ -42,7 +42,6 @@ #include "common/utils.h" - /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ /* Private macro -------------------------------------------------------------*/ @@ -353,7 +352,6 @@ uint8_t usbIsConnected(void) return (bDeviceState != UNCONNECTED); } - /******************************************************************************* * Function Name : CDC_BaudRate. * Description : Get the current baud rate diff --git a/src/platform/STM32/vcp/stm32_it.c b/src/platform/STM32/vcp/stm32_it.c index 3574c9e58..09889b30c 100644 --- a/src/platform/STM32/vcp/stm32_it.c +++ b/src/platform/STM32/vcp/stm32_it.c @@ -57,8 +57,6 @@ void NMI_Handler(void) { } - - /******************************************************************************* * Function Name : MemManage_Handler * Description : This function handles Memory Manage exception. @@ -134,7 +132,6 @@ void PendSV_Handler(void) { } - /******************************************************************************* * Function Name : USB_IRQHandler * Description : This function handles USB Low Priority interrupts diff --git a/src/platform/STM32/vcp_hal/usbd_cdc_interface.c b/src/platform/STM32/vcp_hal/usbd_cdc_interface.c index b44576f8a..f56397676 100644 --- a/src/platform/STM32/vcp_hal/usbd_cdc_interface.c +++ b/src/platform/STM32/vcp_hal/usbd_cdc_interface.c @@ -126,7 +126,6 @@ USBD_CDC_ItfTypeDef USBD_CDC_fops = #endif }; - void TIMx_IRQHandler(void) { HAL_TIM_IRQHandler(&TimHandle); @@ -448,7 +447,6 @@ uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength) return sendLength; } - /******************************************************************************* * Function Name : usbIsConfigured. * Description : Determines if USB VCP is configured or not diff --git a/src/platform/STM32/vcp_hal/usbd_conf_stm32f7xx.c b/src/platform/STM32/vcp_hal/usbd_conf_stm32f7xx.c index 2a730c8e3..24e6cf259 100644 --- a/src/platform/STM32/vcp_hal/usbd_conf_stm32f7xx.c +++ b/src/platform/STM32/vcp_hal/usbd_conf_stm32f7xx.c @@ -379,7 +379,6 @@ void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd) USBD_LL_DevDisconnected(hpcd->pData); } - /******************************************************************************* LL Driver Interface (USB Device Library --> PCD) *******************************************************************************/ @@ -412,7 +411,6 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev) /* Initialize LL Driver */ HAL_PCD_Init(&hpcd); - #ifdef USE_USB_CDC_HID #ifdef USE_USB_MSC if (usbDevConfig()->type == COMPOSITE && !mscCheckBootAndReset()) { diff --git a/src/platform/STM32/vcp_hal/usbd_conf_stm32h7xx.c b/src/platform/STM32/vcp_hal/usbd_conf_stm32h7xx.c index bbe8290c3..10c42ac9b 100644 --- a/src/platform/STM32/vcp_hal/usbd_conf_stm32h7xx.c +++ b/src/platform/STM32/vcp_hal/usbd_conf_stm32h7xx.c @@ -476,7 +476,6 @@ void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef * hpcd) USBD_LL_DevDisconnected(hpcd->pData); } - /******************************************************************************* LL Driver Interface (USB Device Library --> PCD) *******************************************************************************/ diff --git a/src/platform/STM32/vcpf4/usb_bsp.c b/src/platform/STM32/vcpf4/usb_bsp.c index 379a29ce2..28da4eff3 100644 --- a/src/platform/STM32/vcpf4/usb_bsp.c +++ b/src/platform/STM32/vcpf4/usb_bsp.c @@ -41,7 +41,6 @@ void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) (void)state; } - /** * @brief USB_OTG_BSP_Init * Initilizes BSP configurations diff --git a/src/platform/STM32/vcpf4/usb_cdc_hid.c b/src/platform/STM32/vcpf4/usb_cdc_hid.c index d39a92942..8c4b60459 100644 --- a/src/platform/STM32/vcpf4/usb_cdc_hid.c +++ b/src/platform/STM32/vcpf4/usb_cdc_hid.c @@ -18,7 +18,6 @@ * If not, see . */ - #include #include "platform.h" diff --git a/src/platform/STM32/vcpf4/usb_conf.h b/src/platform/STM32/vcpf4/usb_conf.h index abde2e61d..cb2c0498b 100644 --- a/src/platform/STM32/vcpf4/usb_conf.h +++ b/src/platform/STM32/vcpf4/usb_conf.h @@ -26,7 +26,6 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f4xx.h" - /** @addtogroup USB_OTG_DRIVER * @{ */ @@ -65,7 +64,6 @@ //#define USE_I2C_PHY #endif /* USE_I2C_PHY */ - #ifdef USE_USB_OTG_FS #define USB_OTG_FS_CORE #endif @@ -175,14 +173,12 @@ #define USE_DEVICE_MODE // #define USE_OTG_MODE - #ifndef USB_OTG_FS_CORE #ifndef USB_OTG_HS_CORE #error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined" #endif #endif - #ifndef USE_DEVICE_MODE #ifndef USE_HOST_MODE #error "USE_DEVICE_MODE or USE_HOST_MODE should be defined" @@ -242,7 +238,6 @@ * @} */ - /** @defgroup USB_CONF_Exported_Types * @{ */ @@ -250,7 +245,6 @@ * @} */ - /** @defgroup USB_CONF_Exported_Macros * @{ */ @@ -272,10 +266,8 @@ * @} */ - #endif //__USB_CONF__H__ - /** * @} */ diff --git a/src/platform/STM32/vcpf4/usbd_cdc_vcp.c b/src/platform/STM32/vcpf4/usbd_cdc_vcp.c index 4d7e3677c..d3c641e02 100644 --- a/src/platform/STM32/vcpf4/usbd_cdc_vcp.c +++ b/src/platform/STM32/vcpf4/usbd_cdc_vcp.c @@ -72,7 +72,6 @@ static void *ctrlLineStateCbContext; static void (*baudRateCb)(void *context, uint32_t baud); static void *baudRateCbContext; - CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_DataRx }; /* Private functions ---------------------------------------------------------*/ @@ -136,7 +135,6 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) case CLEAR_COMM_FEATURE: break; - //Note - hw flow control on UART 1-3 and 6 only case SET_LINE_CODING: // If a callback is provided, tell the upper driver of changes in baud rate @@ -148,14 +146,12 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) } break; - case GET_LINE_CODING: if (plc && (Len == sizeof(*plc))) { ust_cpy(plc, &g_lc); } break; - case SET_CONTROL_LINE_STATE: // If a callback is provided, tell the upper driver of changes in DTR/RTS state if (plc && (Len == sizeof(uint16_t))) { diff --git a/src/platform/STM32/vcpf4/usbd_cdc_vcp.h b/src/platform/STM32/vcpf4/usbd_cdc_vcp.h index fc27a6d98..d0b7ab1dc 100644 --- a/src/platform/STM32/vcpf4/usbd_cdc_vcp.h +++ b/src/platform/STM32/vcpf4/usbd_cdc_vcp.h @@ -71,5 +71,4 @@ typedef struct __attribute__ ((packed)) uint8_t datatype; } LINE_CODING; - #endif /* __USBD_CDC_VCP_H */ diff --git a/src/platform/STM32/vcpf4/usbd_conf.h b/src/platform/STM32/vcpf4/usbd_conf.h index e29b01958..e98b5d9b7 100644 --- a/src/platform/STM32/vcpf4/usbd_conf.h +++ b/src/platform/STM32/vcpf4/usbd_conf.h @@ -75,7 +75,6 @@ #define MSC_MAX_PACKET 64 #endif - #define MSC_MEDIA_PACKET 4096 /* END MSC */ @@ -91,7 +90,6 @@ * @} */ - /** @defgroup USB_CONF_Exported_Macros * @{ */ @@ -113,7 +111,6 @@ * @} */ - #endif //__USBD_CONF__H__ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/platform/STM32/vcpf4/usbd_desc.c b/src/platform/STM32/vcpf4/usbd_desc.c index 839d8196c..b70edb067 100644 --- a/src/platform/STM32/vcpf4/usbd_desc.c +++ b/src/platform/STM32/vcpf4/usbd_desc.c @@ -35,7 +35,6 @@ * @{ */ - /** @defgroup USBD_DESC * @brief USBD descriptors module * @{ @@ -48,7 +47,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Defines * @{ */ @@ -92,7 +90,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Macros * @{ */ @@ -100,7 +97,6 @@ * @} */ - /** @defgroup USBD_DESC_Private_Variables * @{ */ @@ -199,7 +195,6 @@ __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = * @} */ - /** @defgroup USBD_DESC_Private_FunctionPrototypes * @{ */ @@ -207,7 +202,6 @@ __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = * @} */ - /** @defgroup USBD_DESC_Private_Functions * @{ */ @@ -246,7 +240,6 @@ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) return USBD_LangIDDesc; } - /** * @brief USBD_USR_ProductStrDescriptor * return the product string descriptor @@ -257,7 +250,6 @@ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) { - if (speed == 0) USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); else @@ -314,7 +306,6 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length) return USBD_StrDesc; } - /** * @brief USBD_USR_InterfaceStrDescriptor * return the interface string descriptor @@ -336,12 +327,10 @@ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length) * @} */ - /** * @} */ - /** * @} */ diff --git a/src/platform/STM32/vcpf4/usbd_desc.h b/src/platform/STM32/vcpf4/usbd_desc.h index 90aa0a87f..ed7a71dd2 100644 --- a/src/platform/STM32/vcpf4/usbd_desc.h +++ b/src/platform/STM32/vcpf4/usbd_desc.h @@ -51,7 +51,6 @@ * @} */ - /** @defgroup USBD_DESC_Exported_TypesDefinitions * @{ */ @@ -59,8 +58,6 @@ * @} */ - - /** @defgroup USBD_DESC_Exported_Macros * @{ */ @@ -92,7 +89,6 @@ extern USBD_DEVICE MSC_desc; * @{ */ - uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length); diff --git a/src/platform/STM32/vcpf4/usbd_usr.c b/src/platform/STM32/vcpf4/usbd_usr.c index ce27e0760..f180dff33 100644 --- a/src/platform/STM32/vcpf4/usbd_usr.c +++ b/src/platform/STM32/vcpf4/usbd_usr.c @@ -36,7 +36,6 @@ USBD_Usr_cb_TypeDef USR_cb = USBD_USR_DeviceDisconnected, }; - /** * @brief USBD_USR_Init * Displays the message on LCD for host lib initialization @@ -69,7 +68,6 @@ void USBD_USR_DeviceReset(uint8_t speed ) } } - /** * @brief USBD_USR_DeviceConfigured * Displays the message on LCD on device configuration Event @@ -80,7 +78,6 @@ void USBD_USR_DeviceConfigured (void) { } - /** * @brief USBD_USR_DeviceConnected * Displays the message on LCD on device connection Event @@ -91,7 +88,6 @@ void USBD_USR_DeviceConnected (void) { } - /** * @brief USBD_USR_DeviceDisonnected * Displays the message on LCD on device disconnection Event @@ -113,7 +109,6 @@ void USBD_USR_DeviceSuspended(void) /* Users can do their application actions here for the USB-Reset */ } - /** * @brief USBD_USR_DeviceResumed * Displays the message on LCD on device resume Event diff --git a/src/test/unit/target.h b/src/test/unit/target.h index 90c20c4e3..866d9afe9 100644 --- a/src/test/unit/target.h +++ b/src/test/unit/target.h @@ -66,7 +66,6 @@ #define USE_UART5 #define USE_SOFTSERIAL - #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT #define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 6 // needed for unittest diff --git a/src/test/unit/unittest_macros.h b/src/test/unit/unittest_macros.h index aea1f14a8..2689ad3a0 100644 --- a/src/test/unit/unittest_macros.h +++ b/src/test/unit/unittest_macros.h @@ -17,7 +17,6 @@ #pragma once - #if !defined(UNUSED) #define UNUSED(x) (void)(x) #endif -- 2.11.4.GIT