Merge pull request #754 from martinbudden/bf_tidy_targets_adc

Whitespace and variable initialisation tidy
This commit is contained in:
Martin Budden 2016-07-15 08:35:40 +01:00 committed by GitHub
commit 087aecff79
28 changed files with 477 additions and 500 deletions

View File

@ -24,9 +24,6 @@
#include "build_config.h"
#include "system.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"
@ -84,7 +81,6 @@ void adcInit(drv_adc_config_t *init)
UNUSED(init);
#endif
uint8_t i;
uint8_t configuredAdcChannels = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -117,9 +113,9 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
const adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -163,7 +159,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View File

@ -21,7 +21,6 @@
#include "platform.h"
#include "system.h"
#include "common/utils.h"
#include "gpio.h"
#include "sensor.h"
@ -32,6 +31,8 @@
#include "io.h"
#include "rcc.h"
#include "common/utils.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#endif
@ -100,7 +101,6 @@ void adcInit(drv_adc_config_t *init)
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint8_t i;
uint8_t adcChannelCount = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -135,7 +135,7 @@ void adcInit(drv_adc_config_t *init)
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -203,7 +203,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View File

@ -26,8 +26,6 @@
#include "io_impl.h"
#include "rcc.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"

View File

@ -78,15 +78,14 @@ uint8_t ledPolarity = 0
#endif
;
uint8_t ledOffset = 0;
static uint8_t ledOffset = 0;
void ledInit(bool alternative_led)
{
uint32_t i;
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led)
if (alternative_led) {
ledOffset = LED_NUMBER;
}
#else
UNUSED(alternative_led);
#endif
@ -95,7 +94,7 @@ void ledInit(bool alternative_led)
LED1_OFF;
LED2_OFF;
for (i = 0; i < LED_NUMBER; i++) {
for (int i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
@ -114,6 +113,6 @@ void ledToggle(int led)
void ledSet(int led, bool on)
{
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
}

View File

@ -1,7 +1,7 @@
#pragma once
#define RESOURCE_INDEX(x) x + 1
#define RESOURCE_INDEX(x) (x + 1)
typedef enum {
OWNER_FREE = 0,

View File

@ -28,11 +28,12 @@
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
gyro_t gyro; // gyro access functions

View File

@ -584,10 +584,14 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
uint8_t accHardwareToUse,
uint8_t magHardwareToUse,
uint8_t baroHardwareToUse,
int16_t magDeclinationFromConfig,
uint8_t gyroLpf,
uint8_t gyroSyncDenominator)
{
int16_t deg, min;
memset(&acc, 0, sizeof(acc));
memset(&gyro, 0, sizeof(gyro));
@ -605,7 +609,6 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
detectAcc(accHardwareToUse);
detectBaro(baroHardwareToUse);
// Now time to init things, acc first
if (sensors(SENSOR_ACC)) {
acc.acc_1G = 256; // set default
@ -623,9 +626,8 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
if (sensors(SENSOR_MAG)) {
// calculate magnetic declination
deg = magDeclinationFromConfig / 100;
min = magDeclinationFromConfig % 100;
const int16_t deg = magDeclinationFromConfig / 100;
const int16_t min = magDeclinationFromConfig % 100;
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
} else {
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.

View File

@ -24,10 +24,8 @@
#define LED0 PB5 // Blue LED - PB5
#define BEEPER PA0
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
@ -44,7 +42,6 @@
#define GYRO_MPU6050_ALIGN CW180_DEG
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_GYRO_SPI_MPU6000
@ -52,7 +49,6 @@
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
@ -74,7 +70,6 @@
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 //(AF7)
#define UART3_RX_PIN PB11 //(AF7)

View File

@ -26,14 +26,14 @@
#define HW_PIN PB2
// LED's V1
#define LED0 PB4 // LED - PB4
#define LED1 PB5 // LED - PB5
#define LED0 PB4
#define LED1 PB5
// LED's V2
#define LED0_A PB8 // LED - PB8
#define LED1_A PB9 // LED - PB9
#define LED0_A PB8
#define LED1_A PB9
#define BEEPER PA5 // LED - PA5
#define BEEPER PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -65,7 +65,6 @@
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
#define MAG
#define USE_MAG_AK8963
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define USE_VCP
@ -74,14 +73,14 @@
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2 // PA2
#define UART2_RX_PIN PA3 // PA3
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
@ -130,6 +129,5 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View File

@ -121,9 +121,7 @@
#define SERIAL_PORT_COUNT 4
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13

View File

@ -25,15 +25,15 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_EXTI
#define INVERTER PB15
#define INVERTER_USART USART6
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define BEEPER PB7
#define BEEPER_INVERTED
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define INVERTER PB15
#define INVERTER_USART USART6
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_INSTANCE SPI1

View File

@ -17,13 +17,13 @@
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
#define LED0 PB3 // PB3 (LED)
#define LED0 PB3
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define BEEPER PB15 // PB15 (Beeper)
#define BEEPER_OPT PB2 // PB15 (Beeper)
#define BEEPER PB15
#define BEEPER_OPT PB2
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL

View File

@ -20,9 +20,9 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define LED0 PC14 // PC14 (LED)
#define LED1 PC13 // PC13 (LED)
#define LED2 PC15 // PC15 (LED)
#define LED0 PC14
#define LED1 PC13
#define LED2 PC15
#define ACC
#define USE_ACC_MPU6050

View File

@ -96,8 +96,8 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5

View File

@ -22,10 +22,10 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define BEEPER PA12 // PA12 (Beeper)
#define BEEPER PA12
#ifdef AFROMINI
#define BEEPER_INVERTED
#endif
@ -62,9 +62,7 @@
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
@ -82,7 +80,6 @@
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU3050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
@ -108,7 +105,6 @@
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW180_DEG
#define SONAR

View File

@ -27,7 +27,9 @@
#define LED0 PC14
#define LED1 PC13
#define BEEPER PC13
#define INVERTER PC15
#define INVERTER_USART USART2 //Sbus on USART 2 of nano.
@ -96,6 +98,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) )

View File

@ -88,8 +88,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5

View File

@ -38,12 +38,10 @@
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define BARO
@ -61,11 +59,11 @@
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input.
#define UART2_RX_PIN PA3 // PA3
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -129,7 +127,5 @@
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View File

@ -72,11 +72,11 @@
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -97,8 +97,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -133,4 +133,3 @@
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View File

@ -117,9 +117,8 @@
#define MPU6500_CS_PIN PB9
#define MPU6500_SPI_INSTANCE SPI1
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5

View File

@ -153,7 +153,6 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
#define USE_SERIAL_4WAY_BLHELI_INTERFACE