Skip to content

Commit 3519cda

Browse files
martinbuddendigitalentity
authored andcommitted
Changes to target files to catch up with betaflight (#562)
* Changes to target files to catch up with betaflight * Allow target to define VBAT_SCALE_DEFAULT
1 parent 0f63bc6 commit 3519cda

File tree

12 files changed

+63
-69
lines changed

12 files changed

+63
-69
lines changed

src/main/sensors/battery.h

+4-3
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@
1717

1818
#pragma once
1919

20-
#include "rx/rx.h"
21-
20+
#ifndef VBAT_SCALE_DEFAULT
2221
#define VBAT_SCALE_DEFAULT 110
22+
#endif
2323
#define VBAT_RESDIVVAL_DEFAULT 10
2424
#define VBAT_RESDIVMULTIPLIER_DEFAULT 1
2525
#define VBAT_SCALE_MIN 0
@@ -71,7 +71,8 @@ const char * getBatteryStateString(void);
7171
void updateBattery(uint32_t vbatTimeDelta);
7272
void batteryInit(batteryConfig_t *initialBatteryConfig);
7373

74-
void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
74+
struct rxConfig_s;
75+
void updateCurrentMeter(int32_t lastUpdateAt, struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
7576
int32_t currentMeterToCentiamps(uint16_t src);
7677

7778
uint8_t calculateBatteryPercentage(void);

src/main/target/ALIENFLIGHTF3/target.c

+2-11
Original file line numberDiff line numberDiff line change
@@ -64,28 +64,19 @@ const uint16_t airPWM[] = {
6464

6565

6666
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
67-
// 6 x 3 pin headers
67+
// up to 10 Motor Outputs
6868
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
6969
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
7070
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
7171
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
7272
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
7373
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
74-
75-
// 6 pin header
76-
// PWM7-10
7774
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
7875
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
7976
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
8077
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
8178

8279
// PPM PORT - Also USART2 RX (AF5)
83-
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
84-
//{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
85-
86-
// USART3 RX/TX
87-
// RX conflicts with PPM port
88-
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11
89-
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12
80+
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
9081
};
9182

src/main/target/ALIENFLIGHTF3/target.h

+16-29
Original file line numberDiff line numberDiff line change
@@ -40,27 +40,34 @@
4040
// Using MPU6050 for the moment.
4141
#define GYRO
4242
#define USE_GYRO_MPU6050
43-
#define GYRO_MPU6050_ALIGN CW270_DEG
43+
#define GYRO_MPU6050_ALIGN CW270_DEG
44+
#define USE_GYRO_SPI_MPU6500
45+
#define GYRO_MPU6500_ALIGN CW270_DEG
46+
#define MPU6500_CS_PIN PA15
47+
#define MPU6500_SPI_INSTANCE SPI3
4448

4549
#define ACC
4650
#define USE_ACC_MPU6050
47-
#define ACC_MPU6050_ALIGN CW270_DEG
51+
#define ACC_MPU6050_ALIGN CW270_DEG
52+
#define USE_ACC_SPI_MPU6500
53+
#define ACC_MPU6500_ALIGN CW270_DEG
4854

4955
// No baro support.
5056
//#define BARO
5157
//#define USE_BARO_MS5611
5258

53-
// No mag support for now (option to use MPU9150 in the future).
54-
//#define MAG
55-
//#define USE_MAG_AK8975
56-
//#define MAG_AK8975_ALIGN CW0_DEG_FLIP
59+
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
60+
#define MAG
61+
#define USE_MAG_AK8963
62+
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
63+
#define USE_MAG_HMC5883
5764

5865
#define USE_VCP
5966
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)
6067
#define USE_UART2 // Receiver - RX (PA3)
6168
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
6269
#define SERIAL_PORT_COUNT 4
63-
#define AVOID_UART3_FOR_PWM_PPM
70+
#define AVOID_UART2_FOR_PWM_PPM
6471

6572
#define UART1_TX_PIN PB6
6673
#define UART1_RX_PIN PB7
@@ -86,18 +93,10 @@
8693
#define USE_SPI
8794
#define USE_SPI_DEVICE_3
8895

89-
#define M25P16_CS_PIN PA15
90-
#define M25P16_SPI_INSTANCE SPI3
91-
92-
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
93-
#define MPU6500_CS_PIN PA15
94-
#define MPU6500_SPI_INSTANCE SPI3
95-
9696
#define USE_ADC
9797
#define ADC_INSTANCE ADC2
98-
#define ADC_DMA_CHANNEL DMA2_Channel1
99-
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
10098
#define VBAT_ADC_PIN PA4
99+
#define VBAT_SCALE_DEFAULT 20
101100

102101
#define SPEKTRUM_BIND
103102
// USART2, PA3
@@ -107,25 +106,13 @@
107106
// Hardware bind plug at PB12 (Pin 25)
108107
#define BINDPLUG_PIN PB12
109108

110-
#undef BLACKBOX
111-
112-
#undef GPS
113-
#undef GPS_PROTO_NMEA
114-
#undef GPS_PROTO_UBLOX
115-
#undef GPS_PROTO_I2C_NAV
116-
#undef GPS_PROTO_NAZA
117-
118-
#undef TELEMETRY
119-
#undef TELEMETRY_FRSKY
120-
#undef TELEMETRY_HOTT
121-
#undef TELEMETRY_SMARTPORT
122-
#undef TELEMETRY_LTM
123109

124110
#define BRUSHED_MOTORS
125111
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
126112
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
127113
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
128114
#define SERIALRX_UART SERIAL_PORT_USART3
115+
#define RX_CHANNELS_TAER
129116

130117
// Number of available PWM outputs
131118
#define MAX_PWM_OUTPUT_PORTS 10
+6-4
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,16 @@
11
F3_TARGETS += $(TARGET)
2-
FEATURES = VCP HIGHEND
2+
FEATURES = VCP
33

44
TARGET_SRC = \
55
drivers/accgyro_mpu.c \
66
drivers/accgyro_mpu6050.c \
7+
drivers/accgyro_mpu6500.c \
8+
drivers/accgyro_spi_mpu6500.c \
79
drivers/barometer_bmp085.c \
8-
drivers/barometer_ms5611.c \
910
drivers/barometer_bmp280.c \
11+
drivers/barometer_ms5611.c \
12+
drivers/compass_ak8963.c \
1013
drivers/compass_ak8975.c \
1114
drivers/compass_hmc5883l.c \
12-
drivers/compass_mag3110.c \
13-
drivers/serial_usb_vcp.c
15+
drivers/compass_mag3110.c
1416

src/main/target/BLUEJAYF4/target.c

+7-7
Original file line numberDiff line numberDiff line change
@@ -67,12 +67,12 @@ const uint16_t airPWM[] = {
6767
};
6868

6969
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
70-
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // PPM IN
71-
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S1_OUT
72-
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S2_OUT
73-
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT
74-
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S4_OUT
75-
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
76-
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT
70+
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM IN
71+
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S1_OUT
72+
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S2_OUT
73+
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT
74+
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S4_OUT
75+
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
76+
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT
7777
};
7878

src/main/target/BLUEJAYF4/target.h

-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,6 @@
4343
// MPU6500 interrupt
4444
//#define DEBUG_MPU_DATA_READY_INTERRUPT
4545
#define USE_MPU_DATA_READY_SIGNAL
46-
#define ENSURE_MPU_DATA_READY_IS_LOW
4746
//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
4847
#define MPU_INT_EXTI PC5
4948
#define MPU6500_CS_PIN PC4

src/main/target/COLIBRI_RACE/target.h

+14-8
Original file line numberDiff line numberDiff line change
@@ -34,27 +34,31 @@
3434
#define ENSURE_MPU_DATA_READY_IS_LOW
3535
//#define DEBUG_MPU_DATA_READY_INTERRUPT
3636

37-
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
38-
#define MPU6500_CS_PIN PA4
39-
#define MPU6500_SPI_INSTANCE SPI1
40-
41-
#define MPU6000_CS_PIN PA4
42-
#define MPU6000_SPI_INSTANCE SPI1
4337

4438
#define USE_SPI
4539
#define USE_SPI_DEVICE_1
4640

47-
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
4841
#define SPI1_SCK_PIN PB3
4942
#define SPI1_MISO_PIN PB4
5043
#define SPI1_MOSI_PIN PB5
44+
#define SPI1_NSS_PIN PA4
45+
46+
#define MPU6500_CS_PIN SPI1_NSS_PIN
47+
#define MPU6500_SPI_INSTANCE SPI1
48+
49+
#define MPU6000_CS_PIN SPI1_NSS_PIN
50+
#define MPU6000_SPI_INSTANCE SPI1
5151

5252
#define GYRO
53+
#define USE_GYRO_SPI_MPU6000
54+
#define GYRO_MPU6000_ALIGN CW270_DEG
5355
#define USE_GYRO_MPU6500
5456
#define USE_GYRO_SPI_MPU6500
5557
#define GYRO_MPU6500_ALIGN CW270_DEG
5658

5759
#define ACC
60+
#define USE_ACC_SPI_MPU6000
61+
#define ACC_MPU6000_ALIGN CW270_DEG
5862
#define USE_ACC_MPU6500
5963
#define USE_ACC_SPI_MPU6500
6064
#define ACC_MPU6500_ALIGN CW270_DEG
@@ -65,8 +69,11 @@
6569
#define MAG
6670
#define USE_MPU9250_MAG // Bypass enable
6771
#define USE_MAG_HMC5883
72+
#define USE_MAG_AK8963
6873
#define USE_MAG_AK8975
6974

75+
#define USB_IO
76+
7077
#define USE_VCP
7178
#define USE_UART1
7279
#define USE_UART2
@@ -96,7 +103,6 @@
96103
#define EXTERNAL1_ADC_PIN PC3
97104

98105
#define LED_STRIP
99-
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
100106
#define WS2811_PIN PA6 // TIM16_CH1
101107
#define WS2811_TIMER TIM16
102108
#define WS2811_DMA_CHANNEL DMA1_Channel3

src/main/target/COLIBRI_RACE/target.mk

+2-1
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,11 @@ TARGET_SRC = \
66
drivers/accgyro_mpu6500.c \
77
drivers/accgyro_spi_mpu6000.c \
88
drivers/accgyro_spi_mpu6500.c \
9+
drivers/accgyro_mpu6500.c \
910
drivers/barometer_ms5611.c \
11+
drivers/compass_ak8963.c \
1012
drivers/compass_ak8975.c \
1113
drivers/compass_hmc5883l.c \
12-
drivers/compass_mag3110.c \
1314
drivers/light_ws2811strip.c \
1415
drivers/light_ws2811strip_stm32f30x.c
1516

src/main/target/FURYF3/target.mk

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
F3_TARGETS += $(TARGET)
2-
FEATURES = VCP ONBOARDFLASH HIGHEND SDCARD
2+
FEATURES = VCP ONBOARDFLASH SDCARD
33

44
TARGET_SRC = \
55
drivers/accgyro_mpu.c \

src/main/target/REVO/target.h

+8-3
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,11 @@
5151
#define GYRO_MPU6000_ALIGN CW270_DEG
5252

5353
#define MAG
54+
#define USE_MAG_AK8963
55+
#define USE_MAG_AK8975
5456
#define USE_MAG_HMC5883
5557
#define MAG_HMC5883_ALIGN CW90_DEG
58+
#define USE_MAG_MAG3110
5659

5760
//#define USE_MAG_DATA_READY_SIGNAL
5861
//#define ENSURE_MAG_DATA_READY_IS_HIGH
@@ -62,6 +65,8 @@
6265
//#define MAG_NAZA_ALIGN CW180_DEG_FLIP
6366

6467
#define BARO
68+
#define USE_BARO_BMP085
69+
#define USE_BARO_BMP280
6570
#define USE_BARO_MS5611
6671

6772
//#define PITOT
@@ -75,7 +80,7 @@
7580
#define USE_FLASH_M25P16
7681

7782
#define USE_VCP
78-
#define VBUS_SENSING_PIN PC5
83+
#define VBUS_SENSING_PIN PC5
7984
#define VBUS_SENSING_ENABLED
8085

8186
#define USE_UART1
@@ -104,8 +109,8 @@
104109
#define SPI3_MOSI_PIN PC12
105110

106111
#define USE_I2C
107-
#define I2C_DEVICE (I2CDEV_1)
108-
#define I2C_DEVICE_EXT (I2CDEV_2)
112+
#define I2C_DEVICE (I2CDEV_1)
113+
#define I2C_DEVICE_EXT (I2CDEV_2)
109114

110115
#define USE_ADC
111116
#define CURRENT_METER_ADC_PIN PC1

src/main/target/REVO/target.mk

+2
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@ FEATURES += VCP ONBOARDFLASH
33

44
TARGET_SRC = \
55
drivers/accgyro_spi_mpu6000.c \
6+
drivers/barometer_bmp085.c \
7+
drivers/barometer_bmp280.c \
68
drivers/barometer_ms5611.c \
79
drivers/compass_ak8963.c \
810
drivers/compass_ak8975.c \

src/main/target/STM32F3DISCOVERY/target.mk

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
F3_TARGETS += $(TARGET)
2-
FEATURES = VCP SDCARD HIGHEND
2+
FEATURES = VCP SDCARD
33

44
TARGET_SRC = \
55
drivers/accgyro_adxl345.c \

0 commit comments

Comments
 (0)