diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index f5691c0636..ff3b186cb0 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -51,7 +51,7 @@ typedef struct drv_pwm_config_t { bool airplane; // fixed wing hardware config, lots of servos etc uint16_t motorPwmRate; uint16_t servoPwmRate; - uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm), + 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. uint16_t servoCenterPulse; } drv_pwm_config_t; diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index e5ff523e70..db1af7e867 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -110,7 +110,6 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uartReconfigure(s); - // Receive DMA or IRQ DMA_InitTypeDef DMA_InitStructure; if ((mode & MODE_RX) || (mode & MODE_BIDIR)) { diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index b0887c69a7..2178db42a6 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -381,7 +381,7 @@ void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback * // update overflow callback list // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now) -static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef* tim) { +static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) { timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive; ATOMIC_BLOCK(NVIC_PRIO_TIMER) { for(int i = 0; i < CC_CHANNELS_PER_TIMER; i++) @@ -396,7 +396,7 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef* tim) { } // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive -void timerChConfigCallbacks(const timerHardware_t* timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback) +void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback) { uint8_t timerIndex = lookupTimerIndex(timHw->tim); if (timerIndex >= USED_TIMER_COUNT) { @@ -418,7 +418,7 @@ void timerChConfigCallbacks(const timerHardware_t* timHw, timerCCHandlerRec_t *e // configure callbacks for pair of channels (1+2 or 3+4). // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used. // This is intended for dual capture mode (each channel handles one transition) -void timerChConfigCallbacksDual(const timerHardware_t* timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback) +void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback) { uint8_t timerIndex = lookupTimerIndex(timHw->tim); if (timerIndex >= USED_TIMER_COUNT) { @@ -453,24 +453,24 @@ void timerChConfigCallbacksDual(const timerHardware_t* timHw, timerCCHandlerRec_ } // enable/disable IRQ for low channel in dual configuration -void timerChITConfigDualLo(const timerHardware_t* timHw, FunctionalState newState) { +void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) { TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState); } // enable or disable IRQ -void timerChITConfig(const timerHardware_t* timHw, FunctionalState newState) +void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState) { TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState); } // clear Compare/Capture flag for channel -void timerChClearCCFlag(const timerHardware_t* timHw) +void timerChClearCCFlag(const timerHardware_t *timHw) { TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel)); } // configure timer channel GPIO mode -void timerChConfigGPIO(const timerHardware_t* timHw, GPIO_Mode mode) +void timerChConfigGPIO(const timerHardware_t *timHw, GPIO_Mode mode) { gpio_config_t cfg; @@ -501,7 +501,7 @@ static unsigned getFilter(unsigned ticks) } // Configure input captupre -void timerChConfigIC(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterTicks) +void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { TIM_ICInitTypeDef TIM_ICInitStructure; @@ -517,7 +517,7 @@ void timerChConfigIC(const timerHardware_t* timHw, bool polarityRising, unsigned // configure dual channel input channel for capture // polarity is for Low channel (capture order is always Lo - Hi) -void timerChConfigICDual(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterTicks) +void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { TIM_ICInitTypeDef TIM_ICInitStructure; bool directRising = (timHw->channel & TIM_Channel_2) ? !polarityRising : polarityRising; @@ -537,9 +537,7 @@ void timerChConfigICDual(const timerHardware_t* timHw, bool polarityRising, unsi TIM_ICInit(timHw->tim, &TIM_ICInitStructure); } - - -void timerChICPolarity(const timerHardware_t* timHw, bool polarityRising) +void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising) { timCCER_t tmpccer = timHw->tim->CCER; tmpccer &= ~(TIM_CCER_CC1P << timHw->channel); @@ -547,19 +545,19 @@ void timerChICPolarity(const timerHardware_t* timHw, bool polarityRising) timHw->tim->CCER = tmpccer; } -volatile timCCR_t* timerChCCRHi(const timerHardware_t* timHw) +volatile timCCR_t* timerChCCRHi(const timerHardware_t *timHw) { return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel | TIM_Channel_2)); } -volatile timCCR_t* timerChCCRLo(const timerHardware_t* timHw) +volatile timCCR_t* timerChCCRLo(const timerHardware_t *timHw) { return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_Channel_2)); } -volatile timCCR_t* timerChCCR(const timerHardware_t* timHw) +volatile timCCR_t* timerChCCR(const timerHardware_t *timHw) { return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel); } @@ -599,7 +597,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig -static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t* timerConfig) +static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig) { uint16_t capture; unsigned tim_status; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index c1687b0954..3c6f065625 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -113,7 +113,7 @@ static const char * const mixerNames[] = { "TRI", "QUADP", "QUADX", "BI", "GIMBAL", "Y6", "HEX6", "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX", - "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", + "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER", "CUSTOM", NULL }; @@ -250,7 +250,7 @@ const clivalue_t valueTable[] = { { "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX }, { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX }, - { "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.gpsAutoConfig, 0, GPS_AUTOCONFIG_OFF }, + { "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.gpsAutoConfig, 0, GPS_AUTOCONFIG_OFF }, { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 }, diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 51bfd76415..3e69fde49f 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -96,10 +96,6 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_2) - - - - // #define SOFT_I2C // enable to test software i2c // #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) // #define SOFT_I2C_PB67 diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index b647d28ead..bcf5b36e01 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -351,7 +351,7 @@ void handleSmartPortTelemetry(void) tmpui = 0; // the same ID is sent twice, one for longitude, one for latitude // the MSB of the sent uint32_t helps FrSky keep track - // the even/odd bit of our counter helps us keep track + // the even/odd bit of our counter helps us keep track if (smartPortIdCnt & 1) { tmpui = tmpi = GPS_coord[LON]; if (tmpi < 0) {