diff --git a/src/main/common/printf.h b/src/main/common/printf.h index dff4efdd2d..27615cf56d 100644 --- a/src/main/common/printf.h +++ b/src/main/common/printf.h @@ -119,6 +119,7 @@ int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list #define printf tfp_printf #define sprintf tfp_sprintf +void printfSupportInit(void); void setPrintfSerialPort(serialPort_t *serialPort); #endif diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 202b90e804..69a82a0adb 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -21,7 +21,7 @@ #include "platform.h" #include "system.h" -#include "gpio.h" +#include "io.h" #include "bus_i2c.h" #include "sensor.h" diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 1c705ef137..4284697217 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -29,7 +29,7 @@ #include "nvic.h" #include "system.h" -#include "gpio.h" +#include "io.h" #include "exti.h" #include "bus_i2c.h" diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 132c9e13a0..0b70ebb14a 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -17,6 +17,7 @@ #pragma once +#include "io_types.h" #include "exti.h" // MPU6050 diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index a65abf9128..6bba109396 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -27,6 +27,8 @@ #include "adc.h" #include "adc_impl.h" +#include "common/utils.h" + //#define DEBUG_ADC_CHANNELS #ifdef USE_ADC diff --git a/src/main/drivers/adc.h b/src/main/drivers/adc.h index 55914a3365..47a4b52a0e 100644 --- a/src/main/drivers/adc.h +++ b/src/main/drivers/adc.h @@ -17,7 +17,7 @@ #pragma once -#include "io.h" +#include "io_types.h" typedef enum { ADC_BATTERY = 0, diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 146ada62be..c89dc1bf53 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -17,8 +17,8 @@ #pragma once -#include "io.h" -#include "rcc.h" +#include "io_types.h" +#include "rcc_types.h" #if defined(STM32F4) #define ADC_TAG_MAP_COUNT 16 @@ -65,4 +65,4 @@ extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT]; extern adc_config_t adcConfig[ADC_CHANNEL_COUNT]; extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT]; -uint8_t adcChannelByTag(ioTag_t ioTag); \ No newline at end of file +uint8_t adcChannelByTag(ioTag_t ioTag); diff --git a/src/main/drivers/barometer_ms5611.c b/src/main/drivers/barometer_ms5611.c index 468f86046f..413fe5e980 100644 --- a/src/main/drivers/barometer_ms5611.c +++ b/src/main/drivers/barometer_ms5611.c @@ -22,7 +22,6 @@ #include "barometer.h" -#include "gpio.h" #include "system.h" #include "bus_i2c.h" diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index 104c77c379..42ea8cadc9 100644 --- a/src/main/drivers/bus_i2c_soft.c +++ b/src/main/drivers/bus_i2c_soft.c @@ -22,7 +22,7 @@ #include "build_config.h" #include "bus_i2c.h" -#include "drivers/io.h" +#include "io.h" // Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled. // Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7) diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 9b48aeb76e..3fa55c4512 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -20,9 +20,10 @@ #include -#include "gpio.h" #include "system.h" -#include "drivers/io_impl.h" +#include "io.h" +#include "io_impl.h" +#include "rcc.h" #include "bus_i2c.h" diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c index 0668fcdd77..d5b9a59dec 100755 --- a/src/main/drivers/compass_ak8963.c +++ b/src/main/drivers/compass_ak8963.c @@ -33,9 +33,6 @@ #include "bus_i2c.h" #include "bus_spi.h" -#include "sensors/boardalignment.h" -#include "sensors/sensors.h" - #include "sensor.h" #include "compass.h" diff --git a/src/main/drivers/compass_ak8975.c b/src/main/drivers/compass_ak8975.c index b6664cb0ab..0647e5f231 100644 --- a/src/main/drivers/compass_ak8975.c +++ b/src/main/drivers/compass_ak8975.c @@ -33,8 +33,6 @@ #include "gpio.h" #include "bus_i2c.h" -#include "sensors/sensors.h" - #include "sensor.h" #include "compass.h" @@ -157,4 +155,3 @@ bool ak8975Read(int16_t *magData) return true; } #endif - diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index caea756bc5..10fa9b3c6d 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -39,8 +39,6 @@ #include "sensor.h" #include "compass.h" -#include "sensors/sensors.h" - #include "compass_hmc5883l.h" //#define DEBUG_MAG_DATA_READY_INTERRUPT @@ -274,5 +272,4 @@ bool hmc5883lRead(int16_t *magData) return true; } - #endif diff --git a/src/main/drivers/compass_hmc5883l.h b/src/main/drivers/compass_hmc5883l.h index 035a2c936f..e2f71fd28d 100644 --- a/src/main/drivers/compass_hmc5883l.h +++ b/src/main/drivers/compass_hmc5883l.h @@ -17,7 +17,7 @@ #pragma once -#include "io.h" +#include "io_types.h" typedef struct hmc5883Config_s { ioTag_t intTag; diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index 0ad411312e..7e4942fbe1 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -21,8 +21,8 @@ #include -#include "drivers/nvic.h" -#include "drivers/dma.h" +#include "nvic.h" +#include "dma.h" /* * DMA descriptors. diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index ec6e7908d3..8372ad0bcb 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -21,8 +21,8 @@ #include -#include "drivers/nvic.h" -#include "drivers/dma.h" +#include "nvic.h" +#include "dma.h" /* * DMA descriptors. diff --git a/src/main/drivers/exti.h b/src/main/drivers/exti.h index 8071c65e33..adc95f13ab 100644 --- a/src/main/drivers/exti.h +++ b/src/main/drivers/exti.h @@ -18,7 +18,7 @@ #pragma once -#include "drivers/io.h" +#include "io_types.h" // old EXTI interface, to be replaced typedef struct extiConfig_s { diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index d655646282..5afa4abb76 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -6,16 +6,7 @@ #include #include "resource.h" -// IO pin identification -// make sure that ioTag_t can't be assigned into IO_t without warning -typedef uint8_t ioTag_t; // packet tag to specify IO pin -typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change - -// NONE initializer for ioTag_t variables -#define IOTAG_NONE ((ioTag_t)0) - -// NONE initializer for IO_t variable -#define IO_NONE ((IO_t)0) +#include "io_types.h" // preprocessor is used to convert pinid to requested C data value // compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx) @@ -24,19 +15,6 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin // expand pinid to to ioTag_t #define IO_TAG(pinid) DEFIO_TAG(pinid) -// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin) -// this simplifies initialization (globals are zeroed on start) and allows -// omitting unused fields in structure initializers. -// it is also possible to use IO_t and ioTag_t as boolean value -// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment -// IO_t being pointer is only possibility I know of .. - -// pin config handling -// pin config is packed into ioConfig_t to decrease memory requirements -// IOCFG_x macros are defined for common combinations for all CPUs; this -// helps masking CPU differences - -typedef uint8_t ioConfig_t; // packed IO configuration #if defined(STM32F1) // mode is using only bits 6-2 diff --git a/src/main/drivers/io_types.h b/src/main/drivers/io_types.h new file mode 100644 index 0000000000..ba80cd3bc7 --- /dev/null +++ b/src/main/drivers/io_types.h @@ -0,0 +1,28 @@ +#pragma once + +#include + +// IO pin identification +// make sure that ioTag_t can't be assigned into IO_t without warning +typedef uint8_t ioTag_t; // packet tag to specify IO pin +typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change + +// NONE initializer for ioTag_t variables +#define IOTAG_NONE ((ioTag_t)0) + +// NONE initializer for IO_t variable +#define IO_NONE ((IO_t)0) + +// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin) +// this simplifies initialization (globals are zeroed on start) and allows +// omitting unused fields in structure initializers. +// it is also possible to use IO_t and ioTag_t as boolean value +// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment +// IO_t being pointer is only possibility I know of .. + +// pin config handling +// pin config is packed into ioConfig_t to decrease memory requirements +// IOCFG_x macros are defined for common combinations for all CPUs; this +// helps masking CPU differences + +typedef uint8_t ioConfig_t; // packed IO configuration diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index 6c8f2bb18a..d9c29af370 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -36,8 +36,8 @@ #include "common/color.h" #include "common/colorconversion.h" -#include "drivers/dma.h" -#include "drivers/light_ws2811strip.h" +#include "dma.h" +#include "light_ws2811strip.h" uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE]; volatile uint8_t ws2811LedDataTransferInProgress = 0; diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 4b588a0c9f..911b7cdc66 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -23,10 +23,11 @@ #ifdef LED_STRIP #include "common/color.h" -#include "drivers/light_ws2811strip.h" +#include "light_ws2811strip.h" #include "nvic.h" #include "io.h" #include "dma.h" +#include "rcc.h" #include "timer.h" static IO_t ws2811IO = IO_NONE; diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 8379188f99..1fadfb1f03 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -26,7 +26,7 @@ #include "nvic.h" #include "common/color.h" -#include "drivers/light_ws2811strip.h" +#include "light_ws2811strip.h" #include "dma.h" #include "rcc.h" #include "timer.h" diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index c3d70405ce..1e265d3ffc 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -17,7 +17,7 @@ #pragma once -#include "timer.h" +#include "io_types.h" #if defined(USE_QUAD_MIXER_ONLY) #define MAX_PWM_MOTORS 4 @@ -101,10 +101,11 @@ typedef enum { PWM_PF_PWM = (1 << 6) } pwmPortFlags_e; +struct timerHardware_s; typedef struct pwmPortConfiguration_s { uint8_t index; pwmPortFlags_e flags; - const timerHardware_t *timerHardware; + const struct timerHardware_s *timerHardware; } pwmPortConfiguration_t; typedef struct pwmIOConfiguration_s { @@ -145,4 +146,5 @@ extern const uint16_t multiPWM[]; extern const uint16_t airPPM[]; extern const uint16_t airPWM[]; +pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init); pwmIOConfiguration_t *pwmGetOutputConfiguration(void); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 8177efa7ee..8b8c5853ce 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -27,8 +27,6 @@ #include "io_impl.h" #include "timer.h" -#include "flight/failsafe.h" // FIXME dependency into the main code from a driver - #include "pwm_mapping.h" #include "pwm_output.h" diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 1e2b16e4d7..c3bb4cf6c6 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -30,9 +30,10 @@ #include "system.h" #include "nvic.h" -#include "gpio.h" +#include "io.h" #include "timer.h" +#include "pwm_output.h" #include "pwm_mapping.h" #include "pwm_rx.h" diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h index fb04ec7e2c..4dee74ee79 100644 --- a/src/main/drivers/rcc.h +++ b/src/main/drivers/rcc.h @@ -1,7 +1,6 @@ #pragma once -#include "platform.h" -#include "common/utils.h" +#include "rcc_types.h" enum rcc_reg { RCC_EMPTY = 0, // make sure that default value (0) does not enable anything @@ -17,9 +16,6 @@ enum rcc_reg { #define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) #define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) -typedef uint8_t rccPeriphTag_t; - void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState); void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState); - diff --git a/src/main/drivers/rcc_types.h b/src/main/drivers/rcc_types.h new file mode 100644 index 0000000000..1b7d7b9f2f --- /dev/null +++ b/src/main/drivers/rcc_types.h @@ -0,0 +1,4 @@ +#pragma once + +typedef uint8_t rccPeriphTag_t; + diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 2c2cebbac6..50c6055ddd 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -22,7 +22,7 @@ #include "build_config.h" #include "common/utils.h" -#include "drivers/io.h" +#include "io.h" #include "usb_core.h" #ifdef STM32F4 @@ -32,7 +32,7 @@ #include "hw_config.h" #endif -#include "drivers/system.h" +#include "system.h" #include "serial.h" #include "serial_usb_vcp.h" diff --git a/src/main/drivers/sound_beeper.h b/src/main/drivers/sound_beeper.h index ab7a7c3dfc..9caad4f554 100644 --- a/src/main/drivers/sound_beeper.h +++ b/src/main/drivers/sound_beeper.h @@ -17,7 +17,7 @@ #pragma once -#include "drivers/io.h" +#include "io_types.h" #ifdef BEEPER #define BEEP_TOGGLE systemBeepToggle() diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 08c0835ba5..105a584c44 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -67,4 +67,3 @@ void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn); extern uint32_t cachedRccCsrValue; - diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index bd81852fe0..3e33c545b8 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -28,7 +28,7 @@ #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) // from system_stm32f10x.c -void SetSysClock(void); +void SetSysClock(bool overclock); void systemReset(void) { @@ -70,7 +70,7 @@ void systemInit(void) { checkForBootLoaderRequest(); - SetSysClock(); + SetSysClock(false); #ifdef CC3D /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index fb30936968..16410e658f 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -26,7 +26,7 @@ #include "system.h" #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) -void SetSysClock(); +void SetSysClock(void); void systemReset(void) { diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 5c09ebdf6a..8b48f82f5e 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -22,7 +22,7 @@ #include "platform.h" #include "accgyro_mpu.h" -#include "gpio.h" +#include "exti.h" #include "nvic.h" #include "system.h" diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 15e36cce3f..5051588c99 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -25,7 +25,7 @@ #include "nvic.h" -#include "gpio.h" +#include "io.h" #include "rcc.h" #include "system.h" diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 7050bbabda..00410a9c68 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -17,12 +17,11 @@ #pragma once -#include "io.h" -#include "rcc.h" +#include +#include -#if !defined(USABLE_TIMER_CHANNEL_COUNT) -#define USABLE_TIMER_CHANNEL_COUNT 14 -#endif +#include "io_types.h" +#include "rcc_types.h" typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t) diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c index 1a5085e63a..d918b07112 100644 --- a/src/main/drivers/timer_stm32f10x.c +++ b/src/main/drivers/timer_stm32f10x.c @@ -5,6 +5,13 @@ http://www.st.com/software_license_agreement_liberty_v2 */ +#include +#include + +#include "platform.h" + +#include "common/utils.h" + #include "stm32f10x.h" #include "rcc.h" #include "timer.h" diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index 04069b20c3..871cfb6d78 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -5,6 +5,13 @@ http://www.st.com/software_license_agreement_liberty_v2 */ +#include +#include + +#include "platform.h" + +#include "common/utils.h" + #include "stm32f30x.h" #include "rcc.h" #include "timer.h" diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index af09f85e1b..750324e94a 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -5,9 +5,16 @@ http://www.st.com/software_license_agreement_liberty_v2 */ +#include +#include + +#include "platform.h" + +#include "common/utils.h" + #include "stm32f4xx.h" -#include "timer.h" #include "rcc.h" +#include "timer.h" /** * @brief Selects the TIM Output Compare Mode. diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 25f9aa98d0..fbe8b68344 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -81,6 +81,8 @@ typedef struct failsafeState_s { failsafeRxLinkState_e rxLinkState; } failsafeState_t; +struct rxConfig_s; +void failsafeInit(struct rxConfig_s *intialRxConfig, uint16_t deadband3d_throttle); void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse); failsafeConfig_t * getActiveFailsafeConfig(void); diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 4e20ffff7c..e331ac3997 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -17,8 +17,6 @@ #pragma once -#include "flight/pid.h" - #define GRAVITY_CMSS 980.665f extern int16_t throttleAngleCorrection; @@ -48,7 +46,8 @@ typedef struct imuRuntimeConfig_s { uint8_t small_angle; } imuRuntimeConfig_t; -void imuConfigure(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile); +struct pidProfile_s; +void imuConfigure(imuRuntimeConfig_t *initialImuRuntimeConfig, struct pidProfile_s *initialPidProfile); void imuUpdateGyroAndAttitude(void); void imuUpdateAccelerometer(void); @@ -61,3 +60,4 @@ void imuTransformVectorBodyToEarth(t_fp_vector * v); void imuTransformVectorEarthToBody(t_fp_vector * v); int16_t imuCalculateHeading(t_fp_vector *vec); +void imuInit(void); diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 527316c4bb..e2ee918167 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -235,7 +235,11 @@ void mixerLoadMix(int index, motorMixer_t *customMixers); void servoMixerLoadMix(int index, servoMixer_t *customServoMixers); void loadCustomServoMixer(void); int servoDirection(int servoIndex, int fromChannel); +void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMotorMixers, servoMixer_t *initialCustomServoMixers); +#else +void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers); #endif +void mixerUsePWMIOConfiguration(void); void mixerResetDisarmedMotors(void); void mixTable(void); void writeMotors(void); diff --git a/src/main/io/display.h b/src/main/io/display.h index 6ff3a62004..c8969c7897 100644 --- a/src/main/io/display.h +++ b/src/main/io/display.h @@ -21,6 +21,8 @@ typedef enum { PAGE_STATUS } pageId_e; +struct rxConfig_s; +void displayInit(struct rxConfig_s *intialRxConfig); void updateDisplay(void); void displaySetPage(pageId_e newPageId); diff --git a/src/main/io/gps.h b/src/main/io/gps.h index ff0f3237f1..166821b082 100644 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -132,5 +132,8 @@ typedef struct { extern gpsSolutionData_t gpsSol; extern gpsStatistics_t gpsStats; +void gpsPreInit(gpsConfig_t *initialGpsConfig); +struct serialConfig_s; +void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig); void gpsThread(void); void updateGpsIndicator(uint32_t currentTime); diff --git a/src/main/io/serial_cli.h b/src/main/io/serial_cli.h index d54b04cecf..7c8754a3b9 100644 --- a/src/main/io/serial_cli.h +++ b/src/main/io/serial_cli.h @@ -15,12 +15,12 @@ * along with Cleanflight. If not, see . */ -#ifndef CLI_H_ -#define CLI_H_ +#pragma once extern uint8_t cliMode; +struct serialConfig_s; +void cliInit(struct serialConfig_s *serialConfig); void cliProcess(void); -bool cliIsActiveOnPort(serialPort_t *serialPort); - -#endif /* CLI_H_ */ +struct serialPort_s; +bool cliIsActiveOnPort(struct serialPort_s *serialPort); diff --git a/src/main/main.c b/src/main/main.c index 0e7e470847..0d9018d07d 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -25,6 +25,7 @@ #include "common/color.h" #include "common/atomic.h" #include "common/maths.h" +#include "common/printf.h" #include "drivers/nvic.h" @@ -33,6 +34,7 @@ #include "drivers/dma.h" #include "drivers/exti.h" #include "drivers/gpio.h" +#include "drivers/io.h" #include "drivers/light_led.h" #include "drivers/sound_beeper.h" #include "drivers/timer.h" @@ -43,6 +45,7 @@ #include "drivers/compass.h" #include "drivers/pwm_mapping.h" #include "drivers/pwm_rx.h" +#include "drivers/pwm_output.h" #include "drivers/adc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_spi.h" @@ -55,6 +58,7 @@ #include "drivers/exti.h" #include "rx/rx.h" +#include "rx/spektrum.h" #include "io/beeper.h" #include "io/serial.h" @@ -66,6 +70,8 @@ #include "io/ledstrip.h" #include "io/display.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/serial_msp.h" +#include "io/serial_cli.h" #include "scheduler/scheduler.h" @@ -77,6 +83,7 @@ #include "sensors/battery.h" #include "sensors/boardalignment.h" #include "sensors/initialisation.h" +#include "sensors/sonar.h" #include "telemetry/telemetry.h" #include "blackbox/blackbox.h" @@ -105,27 +112,6 @@ extern uint8_t motorControlEnable; serialPort_t *loopbackPort; #endif -void printfSupportInit(void); -void timerInit(void); -void telemetryInit(void); -void mspInit(); -void cliInit(serialConfig_t *serialConfig); -void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle); -pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init); -#ifdef USE_SERVOS -void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixer_t *customServoMixers); -#else -void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers); -#endif -void mixerUsePWMIOConfiguration(void); -void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions); -void gpsPreInit(gpsConfig_t *initialGpsConfig); -void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig); -void imuInit(void); -void displayInit(rxConfig_t *intialRxConfig); -void spektrumBind(rxConfig_t *rxConfig); -const sonarHcsr04Hardware_t *sonarGetHardwareConfiguration(currentSensor_e currentSensor); - typedef enum { SYSTEM_STATE_INITIALISING = 0, SYSTEM_STATE_CONFIG_LOADED = (1 << 0), @@ -391,6 +377,7 @@ void init(void) adcInit(&adc_params); #endif + initBoardAlignment(&masterConfig.boardAlignment); #ifdef DISPLAY @@ -441,7 +428,7 @@ void init(void) imuInit(); - mspInit(&masterConfig.serialConfig); + mspInit(); #ifdef USE_CLI cliInit(&masterConfig.serialConfig); diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 6af1cb3ffa..5d77922d1d 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -141,6 +141,8 @@ typedef struct rxRuntimeConfig_s { extern rxRuntimeConfig_t rxRuntimeConfig; +struct modeActivationCondition_s; +void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions); void useRxConfig(rxConfig_t *rxConfigToUse); typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data diff --git a/src/main/rx/spektrum.h b/src/main/rx/spektrum.h index 10e4056764..23a68b1217 100644 --- a/src/main/rx/spektrum.h +++ b/src/main/rx/spektrum.h @@ -21,4 +21,7 @@ #define SPEKTRUM_SAT_BIND_MAX 10 uint8_t spektrumFrameStatus(void); -bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); +struct rxConfig_s; +void spektrumBind(struct rxConfig_s *rxConfig); +struct rxRuntimeConfig_s; +bool spektrumInit(struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig, rcReadRawDataPtr *callback); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index ce19be1c86..5475974837 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -24,7 +24,7 @@ #include "common/axis.h" -#include "drivers/gpio.h" +#include "drivers/io.h" #include "drivers/system.h" #include "drivers/exti.h" diff --git a/src/main/sensors/sonar.h b/src/main/sensors/sonar.h index e61b65a64c..68138b5804 100644 --- a/src/main/sensors/sonar.h +++ b/src/main/sensors/sonar.h @@ -18,7 +18,7 @@ #pragma once #include "drivers/sonar_hcsr04.h" -#include "drivers/sonar.h" +#include "drivers/rangefinder.h" #include "sensors/battery.h" typedef enum { @@ -32,7 +32,8 @@ typedef enum { SONAR_HCSR04_PINS_PWM, } sonarHCSR04Pins_e; -typedef void (*sonarInitFunctionPtr)(sonarRange_t *sonarRange); +struct sonarRange_s; +typedef void (*sonarInitFunctionPtr)(struct sonarRange_s *sonarRange); typedef void (*sonarUpdateFunctionPtr)(void); typedef int32_t (*sonarReadFunctionPtr)(void); diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 57fc417638..3a151df75b 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index 4cc13769ea..99d3ab0039 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { #ifdef CC3D_PPM1 diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 631d83e6aa..c2aca46716 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index 0f8228559e..3562e3234d 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index 955f69b6f5..59d5d86c59 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -106,4 +106,5 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c index 15e3b3ec0a..4b0a3250f1 100644 --- a/src/main/target/COLIBRI_RACE/target.c +++ b/src/main/target/COLIBRI_RACE/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/CRAZEPONYMINI/target.c b/src/main/target/CRAZEPONYMINI/target.c index 937dd2e025..2875c44fa9 100644 --- a/src/main/target/CRAZEPONYMINI/target.c +++ b/src/main/target/CRAZEPONYMINI/target.c @@ -21,6 +21,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 (M2) diff --git a/src/main/target/CRAZEPONYMINI/target.h b/src/main/target/CRAZEPONYMINI/target.h index 184adc4fd0..f169f15ae2 100644 --- a/src/main/target/CRAZEPONYMINI/target.h +++ b/src/main/target/CRAZEPONYMINI/target.h @@ -84,4 +84,5 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS TIM_N(2) diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c index b2a0db9a16..0dc2d66044 100644 --- a/src/main/target/EUSTM32F103RC/target.c +++ b/src/main/target/EUSTM32F103RC/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 8fd8bddcb8..927dad1070 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -110,5 +110,6 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index c67b90b621..aad55cfdfb 100755 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -5,6 +5,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 0ba3a670d6..fd8393524a 100755 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -146,8 +146,8 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 +#define I2C1_SCL_PIN PB8 +#define I2C1_SDA_PIN PB9 #define BOARD_HAS_VOLTAGE_DIVIDER #define USE_ADC diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index 15e3b3ec0a..4b0a3250f1 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index a89063cc9a..cc898ba834 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index 7116b53551..dec8739ba0 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 1791f0efb3..e18fec9db6 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -220,4 +220,5 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) ) +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/OLIMEXINO/target.c b/src/main/target/OLIMEXINO/target.c index ca0f265e79..ec7bcd9f2d 100644 --- a/src/main/target/OLIMEXINO/target.c +++ b/src/main/target/OLIMEXINO/target.c @@ -21,6 +21,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 9cbbc5c97e..6017370947 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -95,4 +95,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/PORT103R/target.c b/src/main/target/PORT103R/target.c index 8f21b7cbb7..093fa6ee27 100644 --- a/src/main/target/PORT103R/target.c +++ b/src/main/target/PORT103R/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index 6a73cccdf7..bb8abaa98c 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -128,5 +128,6 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index bd7bbd4c25..cdca6f5a94 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index cc8b87f173..d0aa54c7dd 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -158,4 +158,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 1bea16f50c..c81e7ff70b 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index 389617278b..20b1f185d3 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index bf2a06da44..99f79ec9b7 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input @@ -100,8 +101,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index f6c60d3797..2b1819210e 100755 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 1712bebae2..d2c17db5a2 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -20,6 +20,7 @@ #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" +#include "drivers/timer.h" const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 6feda121bd..ebafe6a585 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -82,5 +82,6 @@ #define TARGET_IO_PORTE 0xffff #define TARGET_IO_PORTF 0x00ff +#define USABLE_TIMER_CHANNEL_COUNT 14 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/STM32F3DISCOVERY/target.mk b/src/main/target/STM32F3DISCOVERY/target.mk index 03dae43122..9c52d2e634 100644 --- a/src/main/target/STM32F3DISCOVERY/target.mk +++ b/src/main/target/STM32F3DISCOVERY/target.mk @@ -5,12 +5,13 @@ TARGET_SRC = \ drivers/accgyro_adxl345.c \ drivers/accgyro_bma280.c \ drivers/accgyro_l3gd20.c \ + drivers/accgyro_l3g4200d.c \ drivers/accgyro_lsm303dlhc.c \ drivers/accgyro_mma845x.c \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu3050.c \ drivers/accgyro_mpu6050.c \ - drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mpu6500.c \ drivers/barometer_bmp280.c \ drivers/barometer_ms5611.c \ drivers/compass_ak8975.c \ diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 901a355dbf..95b18ae5df 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -35,7 +35,7 @@ #include "build_config.h" -#if defined(TELEMETRY) && defined(TELEMETRY_LTM) +#if defined(TELEMETRY_LTM) #include "common/maths.h" #include "common/axis.h" @@ -268,6 +268,7 @@ static void ltm_nframe(void) } #endif +#if defined(GPS) static bool ltm_shouldSendXFrame(void) { static uint16_t lastHDOP = 0; @@ -279,6 +280,7 @@ static bool ltm_shouldSendXFrame(void) return false; } +#endif #define LTM_BIT_AFRAME (1 << 0) #define LTM_BIT_GFRAME (1 << 1) diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index b4585e5fce..b61aa68bd4 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -46,6 +46,7 @@ typedef struct telemetryConfig_s { uint8_t hottAlarmSoundInterval; } telemetryConfig_t; +void telemetryInit(void); bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig); extern serialPort_t *telemetrySharedPort;