diff --git a/flight/pios/inc/stm32f0xx_conf.h b/flight/pios/inc/stm32f0xx_conf.h
index 8d3dc7b43..0af02ca84 100644
--- a/flight/pios/inc/stm32f0xx_conf.h
+++ b/flight/pios/inc/stm32f0xx_conf.h
@@ -1,29 +1,29 @@
/**
- ******************************************************************************
- * @file Project/STM32F0xx_StdPeriph_Templates/stm32f0xx_conf.h
- * @author MCD Application Team
- * @version V1.3.1
- * @date 17-January-2014
- * @brief Library configuration file.
- ******************************************************************************
- * @attention
- *
- *
© COPYRIGHT 2014 STMicroelectronics
- *
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- *
- ******************************************************************************
- */
+ ******************************************************************************
+ * @file Project/STM32F0xx_StdPeriph_Templates/stm32f0xx_conf.h
+ * @author MCD Application Team
+ * @version V1.3.1
+ * @date 17-January-2014
+ * @brief Library configuration file.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT 2014 STMicroelectronics
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F0XX_CONF_H
@@ -32,12 +32,12 @@
/* Includes ------------------------------------------------------------------*/
/* Comment the line below to disable peripheral header file inclusion */
#include "stm32f0xx_adc.h"
-//#include "stm32f0xx_can.h"
-//#include "stm32f0xx_cec.h"
+// #include "stm32f0xx_can.h"
+// #include "stm32f0xx_cec.h"
#include "stm32f0xx_crc.h"
#include "stm32f0xx_crs.h"
-//#include "stm32f0xx_comp.h"
-//#include "stm32f0xx_dac.h"
+// #include "stm32f0xx_comp.h"
+// #include "stm32f0xx_dac.h"
#include "stm32f0xx_dbgmcu.h"
#include "stm32f0xx_dma.h"
#include "stm32f0xx_exti.h"
@@ -53,11 +53,11 @@
#include "stm32f0xx_tim.h"
#include "stm32f0xx_usart.h"
#include "stm32f0xx_wwdg.h"
-#include "stm32f0xx_misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+#include "stm32f0xx_misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
-/* Uncomment the line below to expanse the "assert_param" macro in the
+/* Uncomment the line below to expanse the "assert_param" macro in the
Standard Peripheral Library drivers code */
/* #define USE_FULL_ASSERT 1 */
@@ -65,15 +65,15 @@
#ifdef USE_FULL_ASSERT
/**
- * @brief The assert_param macro is used for function's parameters check.
- * @param expr: If expr is false, it calls assert_failed function which reports
- * the name of the source file and the source line number of the call
- * that failed. If expr is true, it returns no value.
- * @retval None
- */
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function which reports
+ * the name of the source file and the source line number of the call
+ * that failed. If expr is true, it returns no value.
+ * @retval None
+ */
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
- void assert_failed(uint8_t* file, uint32_t line);
+void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
diff --git a/flight/pios/stm32f0x/pios_delay.c b/flight/pios/stm32f0x/pios_delay.c
index dce2ed989..20dff04ae 100644
--- a/flight/pios/stm32f0x/pios_delay.c
+++ b/flight/pios/stm32f0x/pios_delay.c
@@ -36,7 +36,7 @@
#ifdef PIOS_INCLUDE_DELAY
/* these should be defined by CMSIS, but they aren't */
-#define DELAY_COUNTER (TIM2->CNT)
+#define DELAY_COUNTER (TIM2->CNT)
/**
* Initialises the Timer used by PIOS_DELAY functions.
@@ -60,7 +60,7 @@ int32_t PIOS_DELAY_Init(void)
// Stop timer
TIM_Cmd(TIM2, DISABLE);
// Configure timebase and internal clock
- TIM_TimeBaseInit(TIM2, (TIM_TimeBaseInitTypeDef*)&timerInit);
+ TIM_TimeBaseInit(TIM2, (TIM_TimeBaseInitTypeDef *)&timerInit);
TIM_InternalClockConfig(TIM2);
TIM_SetCounter(TIM2, 0);
TIM_Cmd(TIM2, ENABLE);
@@ -164,7 +164,7 @@ uint32_t PIOS_DELAY_GetRaw()
*/
uint32_t PIOS_DELAY_DiffuS(uint32_t raw)
{
- uint32_t diff = - raw;
+ uint32_t diff = -raw;
return diff;
}
diff --git a/flight/pios/stm32f0x/pios_exti.c b/flight/pios/stm32f0x/pios_exti.c
index 049c4eeac..41084e0d9 100644
--- a/flight/pios/stm32f0x/pios_exti.c
+++ b/flight/pios/stm32f0x/pios_exti.c
@@ -98,7 +98,6 @@ uint8_t PIOS_EXTI_gpio_port_to_exti_source_port(GPIO_TypeDef *gpio_port)
case (uint32_t)GPIOE: return EXTI_PortSourceGPIOE;
case (uint32_t)GPIOF: return EXTI_PortSourceGPIOF;
-
}
PIOS_Assert(0);
@@ -166,16 +165,16 @@ int32_t PIOS_EXTI_Init(const struct pios_exti_cfg *cfg)
pios_exti_line_to_cfg_map[line_index] = cfg_index;
/* Initialize the GPIO pin */
- GPIO_Init(cfg->pin.gpio,(GPIO_InitTypeDef*) &cfg->pin.init);
+ GPIO_Init(cfg->pin.gpio, (GPIO_InitTypeDef *)&cfg->pin.init);
/* Set up the EXTI interrupt source */
uint8_t exti_source_port = PIOS_EXTI_gpio_port_to_exti_source_port(cfg->pin.gpio);
uint8_t exti_source_pin = PIOS_EXTI_gpio_pin_to_exti_source_pin(cfg->pin.init.GPIO_Pin);
SYSCFG_EXTILineConfig(exti_source_port, exti_source_pin);
- EXTI_Init((EXTI_InitTypeDef*)&cfg->exti.init);
+ EXTI_Init((EXTI_InitTypeDef *)&cfg->exti.init);
/* Enable the interrupt channel */
- NVIC_Init((NVIC_InitTypeDef*)&cfg->irq.init);
+ NVIC_Init((NVIC_InitTypeDef *)&cfg->irq.init);
return 0;
diff --git a/flight/pios/stm32f0x/pios_gpio.c b/flight/pios/stm32f0x/pios_gpio.c
index f520105fb..17830d2cd 100644
--- a/flight/pios/stm32f0x/pios_gpio.c
+++ b/flight/pios/stm32f0x/pios_gpio.c
@@ -65,7 +65,7 @@ int32_t PIOS_GPIO_Init(uint32_t *gpios_dev_id, const struct pios_gpio_cfg *cfg)
GPIO_PinAFConfig(gpio->pin.gpio, gpio->pin.init.GPIO_Pin, gpio->remap);
}
- GPIO_Init(gpio->pin.gpio, (GPIO_InitTypeDef*)&gpio->pin.init);
+ GPIO_Init(gpio->pin.gpio, (GPIO_InitTypeDef *)&gpio->pin.init);
PIOS_GPIO_Off(*gpios_dev_id, i);
}
@@ -138,12 +138,11 @@ void PIOS_GPIO_Toggle(uint32_t gpios_dev_id, uint8_t gpio_id)
const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
- if (((gpio->pin.gpio->ODR & gpio->pin.init.GPIO_Pin) != 0) ^ gpio->active_low ) {
+ if (((gpio->pin.gpio->ODR & gpio->pin.init.GPIO_Pin) != 0) ^ gpio->active_low) {
PIOS_GPIO_Off(gpios_dev_id, gpio_id);
} else {
PIOS_GPIO_On(gpios_dev_id, gpio_id);
}
-
}
#endif /* PIOS_INCLUDE_GPIO */
diff --git a/flight/pios/stm32f0x/pios_spi.c b/flight/pios/stm32f0x/pios_spi.c
index 9e9841176..5758ce742 100644
--- a/flight/pios/stm32f0x/pios_spi.c
+++ b/flight/pios/stm32f0x/pios_spi.c
@@ -95,14 +95,14 @@ int32_t PIOS_SPI_Init(uint32_t *spi_id, const struct pios_spi_cfg *cfg)
#endif
/* Enable the associated peripheral clock */
switch ((uint32_t)spi_dev->cfg->regs) {
- case (uint32_t)SPI1:
- /* Enable SPI peripheral clock (APB2 == high speed) */
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
- break;
- case (uint32_t)SPI2:
- /* Enable SPI peripheral clock (APB1 == slow speed) */
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
- break;
+ case (uint32_t)SPI1:
+ /* Enable SPI peripheral clock (APB2 == high speed) */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
+ break;
+ case (uint32_t)SPI2:
+ /* Enable SPI peripheral clock (APB1 == slow speed) */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+ break;
}
/* Enable DMA clock */
RCC_AHBPeriphClockCmd(spi_dev->cfg->dma.ahb_clk, ENABLE);
@@ -571,7 +571,7 @@ static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer
SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE);
}
- //TODO: Verify the LDMA_TX and LDMA_RX handling then len is not a multiple of two!!
+ // TODO: Verify the LDMA_TX and LDMA_RX handling then len is not a multiple of two!!
/* Start DMA transfers */
DMA_Cmd(spi_dev->cfg->dma.rx.channel, ENABLE);
diff --git a/flight/pios/stm32f0x/pios_sys.c b/flight/pios/stm32f0x/pios_sys.c
index ad8db9312..a6108353c 100644
--- a/flight/pios/stm32f0x/pios_sys.c
+++ b/flight/pios/stm32f0x/pios_sys.c
@@ -92,7 +92,7 @@ void PIOS_SYS_Init(void)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
- GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14 ); // leave SWD pins alone
+ GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave SWD pins alone
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
@@ -100,7 +100,6 @@ void PIOS_SYS_Init(void)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
GPIO_Init(GPIOC, &GPIO_InitStructure);
-
}
/**
@@ -208,10 +207,9 @@ void NVIC_Configuration(void)
uint32_t *romTable = &pios_isr_vector_table_base;
/* Copy the vector table from the Flash (mapped at the base of the application
- load address 0x0800X000) to the base address of the SRAM at 0x20000000. */
+ load address 0x0800X000) to the base address of the SRAM at 0x20000000. */
- for(uint32_t i = 0; i < 48; i++)
- {
+ for (uint32_t i = 0; i < 48; i++) {
VectorTable[i] = romTable[i];
}
@@ -285,10 +283,9 @@ void UsageFault_Handler(void)
stopHandler();
}
-void stopHandler(){
- while (1)
- {
- }
+void stopHandler()
+{
+ while (1) {}
}
#endif /* PIOS_INCLUDE_SYS */
diff --git a/flight/pios/stm32f0x/pios_usart.c b/flight/pios/stm32f0x/pios_usart.c
index 88fa5ce84..f87fa08c3 100644
--- a/flight/pios/stm32f0x/pios_usart.c
+++ b/flight/pios/stm32f0x/pios_usart.c
@@ -162,8 +162,8 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
}
/* Initialize the USART Rx and Tx pins */
- GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef*)&usart_dev->cfg->rx.init);
- GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef*)&usart_dev->cfg->tx.init);
+ GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
+ GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
/* Enable USART clock */
switch ((uint32_t)usart_dev->cfg->regs) {
@@ -179,7 +179,7 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
}
/* Configure the USART */
- USART_Init(usart_dev->cfg->regs, (USART_InitTypeDef*)&usart_dev->cfg->init);
+ USART_Init(usart_dev->cfg->regs, (USART_InitTypeDef *)&usart_dev->cfg->init);
*usart_id = (uint32_t)usart_dev;
@@ -195,7 +195,7 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
PIOS_USART_3_id = (uint32_t)usart_dev;
break;
}
- NVIC_Init((NVIC_InitTypeDef*)&usart_dev->cfg->irq.init);
+ NVIC_Init((NVIC_InitTypeDef *)&usart_dev->cfg->irq.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
diff --git a/flight/uavobjects/uavobjectmanager.c b/flight/uavobjects/uavobjectmanager.c
index 6cdc8a48c..384f2c919 100644
--- a/flight/uavobjects/uavobjectmanager.c
+++ b/flight/uavobjects/uavobjectmanager.c
@@ -893,11 +893,13 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId)
}
#else // PIOS_INCLUDE_FLASH
-int32_t UAVObjSave(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId){
+int32_t UAVObjSave(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId)
+{
return 0;
}
-int32_t UAVObjLoad(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId){
+int32_t UAVObjLoad(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId)
+{
return 0;
}