Minor cosmetic tidying

This commit is contained in:
Martin Budden 2016-06-27 20:04:21 +01:00
parent 2b27016f51
commit a2d1af04aa
7 changed files with 15 additions and 17 deletions

View File

@ -17,7 +17,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
@ -26,7 +25,6 @@
#include "nvic.h" #include "nvic.h"
#include "gpio.h"
#include "gpio.h" #include "gpio.h"
#include "rcc.h" #include "rcc.h"
#include "system.h" #include "system.h"

View File

@ -17,11 +17,11 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include <string.h> #include <string.h>
#include <math.h> #include <math.h>
#include "platform.h" #include "platform.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h" #include "common/maths.h"
@ -153,9 +153,6 @@ static uint8_t systemState = SYSTEM_STATE_INITIALISING;
void init(void) void init(void)
{ {
uint8_t i;
drv_pwm_config_t pwm_params;
printfSupportInit(); printfSupportInit();
initEEPROM(); initEEPROM();
@ -260,6 +257,7 @@ void init(void)
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer); mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
#endif #endif
drv_pwm_config_t pwm_params;
memset(&pwm_params, 0, sizeof(pwm_params)); memset(&pwm_params, 0, sizeof(pwm_params));
#ifdef SONAR #ifdef SONAR
@ -333,6 +331,7 @@ void init(void)
#endif #endif
pwmRxInit(masterConfig.inputFilteringMode); pwmRxInit(masterConfig.inputFilteringMode);
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params); pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
@ -504,7 +503,7 @@ void init(void)
LED0_OFF; LED0_OFF;
LED2_OFF; LED2_OFF;
for (i = 0; i < 10; i++) { for (int i = 0; i < 10; i++) {
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;
delay(25); delay(25);

View File

@ -45,7 +45,7 @@ acc_t acc; // acc access functions
sensor_align_e accAlign = 0; sensor_align_e accAlign = 0;
uint32_t accTargetLooptime; uint32_t accTargetLooptime;
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
extern uint16_t InflightcalibratingA; extern uint16_t InflightcalibratingA;
extern bool AccInflightCalibrationArmed; extern bool AccInflightCalibrationArmed;

View File

@ -20,6 +20,10 @@
#include <math.h> #include <math.h>
#include "platform.h" #include "platform.h"
int32_t BaroAlt = 0;
#ifdef BARO
#include "common/maths.h" #include "common/maths.h"
#include "drivers/barometer.h" #include "drivers/barometer.h"
@ -32,9 +36,6 @@ baro_t baro; // barometer access functions
uint16_t calibratingB = 0; // baro calibration = get new ground pressure value uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
int32_t baroPressure = 0; int32_t baroPressure = 0;
int32_t baroTemperature = 0; int32_t baroTemperature = 0;
int32_t BaroAlt = 0;
#ifdef BARO
static int32_t baroGroundAltitude = 0; static int32_t baroGroundAltitude = 0;
static int32_t baroGroundPressure = 0; static int32_t baroGroundPressure = 0;

View File

@ -40,13 +40,14 @@
#endif #endif
mag_t mag; // mag access functions mag_t mag; // mag access functions
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead. extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
int16_t magADCRaw[XYZ_AXIS_COUNT]; static int16_t magADCRaw[XYZ_AXIS_COUNT];
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
static uint8_t magInit = 0; static uint8_t magInit = 0;
void compassInit(void) void compassInit(void)

View File

@ -84,7 +84,6 @@ const uint16_t airPWM[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // 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, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1

View File

@ -17,7 +17,7 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "X_RACERSPI" #define TARGET_BOARD_IDENTIFIER "XRC3"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE