diff --git a/src/main/common/printf.h b/src/main/common/printf.h index dff4efdd2..ac5493590 100644 --- a/src/main/common/printf.h +++ b/src/main/common/printf.h @@ -120,5 +120,7 @@ int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list #define sprintf tfp_sprintf void setPrintfSerialPort(serialPort_t *serialPort); +void printfSupportInit(void); + #endif diff --git a/src/main/drivers/accgyro_lsm303dlhc.c b/src/main/drivers/accgyro_lsm303dlhc.c index c3ea4968e..80a270b9f 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.c +++ b/src/main/drivers/accgyro_lsm303dlhc.c @@ -19,6 +19,9 @@ #include #include "platform.h" + +#ifdef USE_ACC_LSM303DLHC + #include "debug.h" #include "common/maths.h" @@ -167,4 +170,4 @@ bool lsm303dlhcAccDetect(acc_t *acc) acc->read = lsm303dlhcAccRead; return true; } - +#endif diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 524df1bc8..88b267f11 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -132,10 +132,10 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) } } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write); - /* Wait until TXIS flag is set */ + /* Wait until TXIS flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { if ((i2cTimeout--) == 0) { @@ -143,10 +143,10 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) } } - /* Send Register address */ + /* Send Register address */ I2C_SendData(I2Cx, (uint8_t) reg); - /* Wait until TCR flag is set */ + /* Wait until TCR flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) { @@ -155,10 +155,10 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) } } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop); - /* Wait until TXIS flag is set */ + /* Wait until TXIS flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { if ((i2cTimeout--) == 0) { @@ -166,10 +166,10 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) } } - /* Write data to TXDR */ + /* Write data to TXDR */ I2C_SendData(I2Cx, data); - /* Wait until STOPF flag is set */ + /* Wait until STOPF flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { if ((i2cTimeout--) == 0) { @@ -177,7 +177,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) } } - /* Clear STOPF flag */ + /* Clear STOPF flag */ I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); return true; @@ -198,10 +198,10 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* } } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write); - /* Wait until TXIS flag is set */ + /* Wait until TXIS flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { if ((i2cTimeout--) == 0) { @@ -209,10 +209,10 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* } } - /* Send Register address */ + /* Send Register address */ I2C_SendData(I2Cx, (uint8_t) reg); - /* Wait until TC flag is set */ + /* Wait until TC flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) { if ((i2cTimeout--) == 0) { @@ -220,10 +220,10 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* } } - /* Configure slave address, nbytes, reload, end mode and start or stop generation */ + /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read); - /* Wait until all data are received */ + /* Wait until all data are received */ while (len) { /* Wait until RXNE flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; @@ -233,16 +233,16 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* } } - /* Read data from RXDR */ + /* Read data from RXDR */ *buf = I2C_ReceiveData(I2Cx); /* Point to the next location where the byte read will be saved */ buf++; - /* Decrement the read bytes counter */ + /* Decrement the read bytes counter */ len--; } - /* Wait until STOPF flag is set */ + /* Wait until STOPF flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { if ((i2cTimeout--) == 0) { @@ -250,10 +250,10 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* } } - /* Clear STOPF flag */ + /* Clear STOPF flag */ I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); - /* If all operations OK */ + /* If all operations OK */ return true; } diff --git a/src/main/drivers/compass_ak8975.c b/src/main/drivers/compass_ak8975.c index c35db1d1f..0d648ecc5 100644 --- a/src/main/drivers/compass_ak8975.c +++ b/src/main/drivers/compass_ak8975.c @@ -20,10 +20,12 @@ #include -#include "build_config.h" - #include "platform.h" +#ifdef USE_MAG_AK8975 + +#include "build_config.h" + #include "common/axis.h" #include "common/maths.h" @@ -31,7 +33,6 @@ #include "gpio.h" #include "bus_i2c.h" -#include "sensors/boardalignment.h" #include "sensors/sensors.h" #include "sensor.h" @@ -59,7 +60,7 @@ #define AK8975_MAG_REG_CNTL 0x0a #define AK8975_MAG_REG_ASCT 0x0c // self test -bool ak8975detect(mag_t *mag) +bool ak8975Detect(mag_t *mag) { bool ack = false; uint8_t sig = 0; @@ -155,3 +156,4 @@ bool ak8975Read(int16_t *magData) ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again return true; } +#endif diff --git a/src/main/drivers/compass_ak8975.h b/src/main/drivers/compass_ak8975.h index f80e64613..493114cb3 100644 --- a/src/main/drivers/compass_ak8975.h +++ b/src/main/drivers/compass_ak8975.h @@ -17,6 +17,6 @@ #pragma once -bool ak8975detect(mag_t *mag); +bool ak8975Detect(mag_t *mag); void ak8975Init(void); bool ak8975Read(int16_t *magData); diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index 68c404d80..3709cc510 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -21,6 +21,9 @@ #include #include "platform.h" + +#ifdef USE_MAG_HMC5883 + #include "debug.h" #include "common/axis.h" @@ -271,3 +274,4 @@ bool hmc5883lRead(int16_t *magData) return true; } +#endif diff --git a/src/main/drivers/inverter.h b/src/main/drivers/inverter.h index 6ec27ef83..4b9c3fe27 100644 --- a/src/main/drivers/inverter.h +++ b/src/main/drivers/inverter.h @@ -28,5 +28,3 @@ void inverterSet(bool on); void initInverter(void); - - diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 980168abb..0ba9d9169 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -54,14 +54,14 @@ const struct ioPortDef_s ioPortDefs[] = { # endif const char * const ownerNames[OWNER_TOTAL_COUNT] = { - "FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER", - "SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD", - "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER" + "FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER", + "SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD", + "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER" }; const char * const resourceNames[RESOURCE_TOTAL_COUNT] = { - "", // NONE - "IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL", + "", // NONE + "IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL", "SDA", "SCK","MOSI","MISO","CS","BATTERY","RSSI","EXT","CURRENT" }; diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index 05f099892..6c8f2bb18 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -30,6 +30,8 @@ #include +#ifdef LED_STRIP + #include "build_config.h" #include "common/color.h" @@ -37,8 +39,6 @@ #include "drivers/dma.h" #include "drivers/light_ws2811strip.h" -#ifdef LED_STRIP - 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 b4a9b5426..4b588a0c9 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -20,6 +20,8 @@ #include +#ifdef LED_STRIP + #include "common/color.h" #include "drivers/light_ws2811strip.h" #include "nvic.h" @@ -27,8 +29,6 @@ #include "dma.h" #include "timer.h" -#ifdef LED_STRIP - static IO_t ws2811IO = IO_NONE; bool ws2811Initialised = false; diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 722dd9a2e..8379188f9 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -20,6 +20,8 @@ #include +#ifdef LED_STRIP + #include "io.h" #include "nvic.h" @@ -29,8 +31,6 @@ #include "rcc.h" #include "timer.h" -#ifdef LED_STRIP - #ifndef WS2811_PIN #define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index e8676e2cd..63bcd9cee 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef LED_STRIP + #include "common/color.h" #include "light_ws2811strip.h" #include "nvic.h" @@ -29,8 +31,6 @@ #include "rcc.h" #include "timer.h" -#ifdef LED_STRIP - #if !defined(WS2811_PIN) #define WS2811_PIN PA0 #define WS2811_TIMER TIM5 diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 3cec1ab3e..3f88e3a47 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -89,7 +89,6 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void) pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) { - int i = 0; const uint16_t *setup; #ifndef SKIP_RX_PWM_PPM @@ -99,6 +98,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration)); // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] + int i = 0; if (init->airplane) i = 2; // switch to air hardware config if (init->usePPM || init->useSerialRx) @@ -177,8 +177,8 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #ifdef SONAR if (init->useSonar && ( - timerHardwarePtr->tag == init->sonarConfig.triggerTag || - timerHardwarePtr->tag == init->sonarConfig.echoTag + timerHardwarePtr->tag == init->sonarIOConfig.triggerTag || + timerHardwarePtr->tag == init->sonarIOConfig.echoTag )) { continue; } diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 5a3f402e9..29a5d02f1 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -68,9 +68,10 @@ typedef struct drv_pwm_config_s { uint16_t motorPwmRate; uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm), // some higher value (used by 3d mode), or 0, for brushed pwm drivers. - sonarIOConfig_t sonarConfig; + sonarIOConfig_t sonarIOConfig; } drv_pwm_config_t; + enum { MAP_TO_PPM_INPUT = 1, MAP_TO_PWM_INPUT, @@ -136,4 +137,5 @@ extern const uint16_t airPPM_BP6[]; extern const uint16_t airPWM_BP6[]; #endif +pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init); pwmOutputConfiguration_t *pwmGetOutputConfiguration(void); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 44504f680..f470137a7 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -71,12 +71,11 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8 TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; if (output & TIMER_OUTPUT_N_CHANNEL) { - TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable; - TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; - } - else { - TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; - TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; + } else { + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; } TIM_OCInitStructure.TIM_Pulse = value; TIM_OCInitStructure.TIM_OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_High : TIM_OCPolarity_Low; @@ -175,7 +174,7 @@ void pwmWriteMotor(uint8_t index, uint16_t value) void pwmShutdownPulsesForAllMotors(uint8_t motorCount) { - for(int index = 0; index < motorCount; index++){ + for (int index = 0; index < motorCount; index++) { // Set the compare register to 0, which stops the output pulsing if the timer overflows *motors[index]->ccr = 0; } @@ -197,13 +196,13 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) bool overflowed = false; // If we have not already overflowed this timer for (int j = 0; j < index; j++) { - if (motors[j]->tim == motors[index]->tim) { - overflowed = true; - break; - } + if (motors[j]->tim == motors[index]->tim) { + overflowed = true; + break; + } } if (!overflowed) { - timerForceOverflow(motors[index]->tim); + timerForceOverflow(motors[index]->tim); } // Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again. // This compare register will be set to the output value on the next main loop. diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 51cdeb293..d8fafdf78 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -470,14 +470,16 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance) const struct serialPortVTable softSerialVTable[] = { { - softSerialWriteByte, - softSerialRxBytesWaiting, - softSerialTxBytesFree, - softSerialReadByte, - softSerialSetBaudRate, - isSoftSerialTransmitBufferEmpty, - softSerialSetMode, + .serialWrite = softSerialWriteByte, + .serialTotalRxWaiting = softSerialRxBytesWaiting, + .serialTotalTxFree = softSerialTxBytesFree, + .serialRead = softSerialReadByte, + .serialSetBaudRate = softSerialSetBaudRate, + .isSerialTransmitBufferEmpty = isSoftSerialTransmitBufferEmpty, + .setMode = softSerialSetMode, .writeBuf = NULL, + .beginWrite = NULL, + .endWrite = NULL } }; diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index c6d58aa74..105a584c4 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -67,5 +67,3 @@ void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn); extern uint32_t cachedRccCsrValue; - - diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 501c16845..d166e1c36 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -70,6 +70,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); void failsafeStartMonitoring(void); diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 6dc0a1f6b..94b361fcf 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -88,3 +88,4 @@ int16_t imuCalculateHeading(t_fp_vector *vec); void imuResetAccelerationSum(void); void imuUpdateAcc(rollAndPitchTrims_t *accelerometerTrims); +void imuInit(void); diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index b76aafa1b..bf1293e73 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -206,10 +206,15 @@ void mixerUseConfigs( void writeAllMotors(int16_t mc); void mixerLoadMix(int index, motorMixer_t *customMixers); #ifdef USE_SERVOS +void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixer_t *customServoMixers); void servoMixerLoadMix(int index, servoMixer_t *customServoMixers); void loadCustomServoMixer(void); int servoDirection(int servoIndex, int fromChannel); +#else +void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers); #endif +struct pwmOutputConfiguration_s; +void mixerUsePWMOutputConfiguration(struct pwmOutputConfiguration_s *pwmOutputConfiguration, bool use_unsyncedPwm); void mixerResetDisarmedMotors(void); void mixTable(void *pidProfilePtr); void syncMotors(bool enabled); diff --git a/src/main/flight/navigation.h b/src/main/flight/navigation.h index 673cf5cfb..8adb9918d 100644 --- a/src/main/flight/navigation.h +++ b/src/main/flight/navigation.h @@ -46,6 +46,8 @@ extern int16_t GPS_directionToHome; // direction to home or hol point in extern navigationMode_e nav_mode; // Navigation mode +struct pidProfile_s; +void navigationInit(gpsProfile_t *initialGpsProfile, struct pidProfile_s *pidProfile); void GPS_reset_home_position(void); void GPS_reset_nav(void); void GPS_set_next_wp(int32_t* lat, int32_t* lon); diff --git a/src/main/io/display.h b/src/main/io/display.h index 8149a35ad..5582dc512 100644 --- a/src/main/io/display.h +++ b/src/main/io/display.h @@ -35,6 +35,8 @@ typedef enum { #endif } pageId_e; +struct rxConfig_s; +void displayInit(struct rxConfig_s *intialRxConfig); void updateDisplay(void); void displayShowFixedPage(pageId_e pageId); diff --git a/src/main/io/gps.h b/src/main/io/gps.h index cdb9f66f6..efa0ec32c 100644 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -117,7 +117,8 @@ extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Str #define GPS_DBHZ_MIN 0 #define GPS_DBHZ_MAX 55 - +struct serialConfig_s; +void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig); void gpsThread(void); bool gpsNewFrame(uint8_t c); void updateGpsIndicator(uint32_t currentTime); diff --git a/src/main/io/serial_cli.h b/src/main/io/serial_cli.h index d54b04cec..f2ec866a6 100644 --- a/src/main/io/serial_cli.h +++ b/src/main/io/serial_cli.h @@ -20,6 +20,8 @@ extern uint8_t cliMode; +struct serialConfig_s; +void cliInit(struct serialConfig_s *serialConfig); void cliProcess(void); bool cliIsActiveOnPort(serialPort_t *serialPort); diff --git a/src/main/main.c b/src/main/main.c index 79e415c1c..6597ea767 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -25,6 +25,7 @@ #include "common/axis.h" #include "common/color.h" #include "common/maths.h" +#include "common/printf.h" #include "drivers/nvic.h" @@ -61,6 +62,7 @@ #endif #include "rx/rx.h" +#include "rx/spektrum.h" #include "io/beeper.h" #include "io/serial.h" @@ -72,6 +74,8 @@ #include "io/ledstrip.h" #include "io/display.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/serial_cli.h" +#include "io/serial_msp.h" #include "io/transponder_ir.h" #include "io/osd.h" #include "io/vtx.h" @@ -115,28 +119,6 @@ extern uint8_t motorControlEnable; serialPort_t *loopbackPort; #endif -void printfSupportInit(void); -void timerInit(void); -void telemetryInit(void); -void mspInit(serialConfig_t *serialConfig); -void cliInit(serialConfig_t *serialConfig); -void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle); -pwmOutputConfiguration_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 mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfiguration, bool use_unsyncedPwm); -void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions); -void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig); -void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile); -void imuInit(void); -void displayInit(rxConfig_t *intialRxConfig); -void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, modeColorIndexes_t *modeColorsToUse, specialColorIndexes_t *specialColorsToUse); -void spektrumBind(rxConfig_t *rxConfig); -const sonarHardware_t *sonarGetHardwareConfiguration(currentSensor_e currentSensor); -void osdInit(void); typedef enum { SYSTEM_STATE_INITIALISING = 0, @@ -270,8 +252,8 @@ void init(void) const sonarHardware_t *sonarHardware = sonarGetHardwareConfiguration(masterConfig.batteryConfig.currentMeterType); if (sonarHardware) { pwm_params.useSonar = true; - pwm_params.sonarConfig.triggerTag = sonarHardware->triggerTag; - pwm_params.sonarConfig.echoTag = sonarHardware->echoTag; + pwm_params.sonarIOConfig.triggerTag = sonarHardware->triggerTag; + pwm_params.sonarIOConfig.echoTag = sonarHardware->echoTag; } } #endif diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 60625f608..1200e5e8f 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -143,10 +143,11 @@ typedef struct rxRuntimeConfig_s { extern rxRuntimeConfig_t rxRuntimeConfig; -void useRxConfig(rxConfig_t *rxConfigToUse); - typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data +struct modeActivationCondition_s; +void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions); +void useRxConfig(rxConfig_t *rxConfigToUse); void updateRx(uint32_t currentTime); bool rxIsReceivingSignal(void); bool rxAreFlightChannelsValid(void); diff --git a/src/main/rx/spektrum.h b/src/main/rx/spektrum.h index 82989ea55..5481bdebc 100644 --- a/src/main/rx/spektrum.h +++ b/src/main/rx/spektrum.h @@ -21,3 +21,6 @@ #define SPEKTRUM_SAT_BIND_MAX 10 uint8_t spektrumFrameStatus(void); +struct rxConfig_s; +void spektrumBind(struct rxConfig_s *rxConfig); + diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 9d6afab5d..f459a3bcc 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -17,7 +17,6 @@ #pragma once -#include "rx/rx.h" #include "common/maths.h" #ifndef VBAT_SCALE_DEFAULT @@ -75,7 +74,8 @@ void updateBattery(void); void batteryInit(batteryConfig_t *initialBatteryConfig); batteryConfig_t *batteryConfig; -void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t deadband3d_throttle); +struct rxConfig_s; +void updateCurrentMeter(int32_t lastUpdateAt, struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle); int32_t currentMeterToCentiamps(uint16_t src); fix12_t calculateVbatPidCompensation(void); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 38d81a1f4..bb46059ac 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -537,7 +537,7 @@ retry: case MAG_AK8975: #ifdef USE_MAG_AK8975 - if (ak8975detect(&mag)) { + if (ak8975Detect(&mag)) { #ifdef MAG_AK8975_ALIGN magAlign = MAG_AK8975_ALIGN; #endif diff --git a/src/main/sensors/sonar.h b/src/main/sensors/sonar.h index be49afb7b..0c0849e32 100644 --- a/src/main/sensors/sonar.h +++ b/src/main/sensors/sonar.h @@ -17,12 +17,16 @@ #pragma once +#include "sensors/battery.h" + #define SONAR_OUT_OF_RANGE (-1) extern int16_t sonarMaxRangeCm; extern int16_t sonarCfAltCm; extern int16_t sonarMaxAltWithTiltCm; +struct sonarHardware_s; +const struct sonarHardware_s *sonarGetHardwareConfiguration(currentSensor_e currentSensor); void sonarInit(void); void sonarUpdate(void); int32_t sonarRead(void); diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index b4585e5fc..b61aa68bd 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;