Skip to content

Commit 1c2b8fd

Browse files
authored
Merge pull request #8943 from YI-BOYANG/master
Add the "GEPRCF722_BT_HD" target
2 parents 2bdd570 + ab2ae54 commit 1c2b8fd

File tree

4 files changed

+290
-0
lines changed

4 files changed

+290
-0
lines changed
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
target_stm32f722xe(GEPRCF722_BT_HD)
Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
/*
2+
* This file is part of INAV.
3+
*
4+
* INAV is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* INAV is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
16+
*/
17+
18+
#include <stdbool.h>
19+
#include <stdint.h>
20+
21+
#include <platform.h>
22+
23+
#include "common/axis.h"
24+
25+
#include "config/config_master.h"
26+
#include "config/feature.h"
27+
28+
#include "drivers/sensor.h"
29+
#include "drivers/pwm_esc_detect.h"
30+
#include "drivers/pwm_output.h"
31+
#include "drivers/serial.h"
32+
33+
#include "fc/rc_controls.h"
34+
35+
#include "flight/failsafe.h"
36+
#include "flight/mixer.h"
37+
#include "flight/pid.h"
38+
39+
#include "rx/rx.h"
40+
41+
#include "io/serial.h"
42+
43+
#include "sensors/battery.h"
44+
#include "sensors/sensors.h"
45+
46+
#include "telemetry/telemetry.h"
47+
48+
#include "fc/fc_msp_box.h"
49+
50+
#include "io/piniobox.h"
51+
52+
53+
#define BLUETOOTH_MSP_BAUDRATE BAUD_115200
54+
55+
void targetConfiguration(void)
56+
{
57+
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER1;
58+
59+
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP;
60+
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE;
61+
}
62+
Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
/*
2+
* This file is part of INAV Project.
3+
*
4+
* INAV is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* INAV is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
16+
*/
17+
18+
#include <stdint.h>
19+
20+
#include "platform.h"
21+
22+
#include "drivers/bus.h"
23+
#include "drivers/io.h"
24+
#include "drivers/pwm_mapping.h"
25+
#include "drivers/timer.h"
26+
#include "drivers/sensor.h"
27+
28+
29+
30+
timerHardware_t timerHardware[] = {
31+
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
32+
33+
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
34+
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
35+
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
36+
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
37+
38+
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0),
39+
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0),
40+
41+
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0),
42+
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0),
43+
44+
DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0),
45+
};
46+
47+
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
Lines changed: 180 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,180 @@
1+
/*
2+
* This file is part of INAV Project.
3+
*
4+
* INAV is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* INAV is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
16+
*/
17+
18+
#pragma once
19+
20+
#define TARGET_BOARD_IDENTIFIER "GEPR"
21+
22+
#define USBD_PRODUCT_STRING "GEPRCF722_BT_HD"
23+
24+
#define LED0 PC4
25+
26+
#define BEEPER PC15
27+
#define BEEPER_INVERTED
28+
29+
// *************** Gyro & ACC **********************
30+
31+
#define USE_SPI
32+
#define USE_SPI_DEVICE_1
33+
34+
#define SPI1_SCK_PIN PA5
35+
#define SPI1_MISO_PIN PA6
36+
#define SPI1_MOSI_PIN PA7
37+
38+
39+
#define USE_IMU_MPU6000
40+
#define IMU_MPU6000_ALIGN CW0_DEG
41+
#define MPU6000_CS_PIN PA15
42+
#define MPU6000_SPI_BUS BUS_SPI1
43+
#define MPU6000_EXTI_PIN PA8
44+
45+
#define USE_IMU_BMI270
46+
#define IMU_BMI270_ALIGN CW0_DEG
47+
#define BMI270_CS_PIN PA15
48+
#define BMI270_SPI_BUS BUS_SPI1
49+
#define BMI270_EXTI_PIN PA8
50+
51+
#define USE_IMU_ICM42605
52+
#define IMU_ICM42605_ALIGN CW0_DEG
53+
#define ICM42605_CS_PIN PA15
54+
#define ICM42605_SPI_BUS BUS_SPI1
55+
#define ICM42605_EXTI_PIN PA8
56+
57+
#define USE_EXTI
58+
#define USE_MPU_DATA_READY_SIGNAL
59+
60+
// *************** I2C/Baro/Mag *********************
61+
#define USE_I2C
62+
#define USE_I2C_DEVICE_2
63+
#define I2C2_SCL PB10
64+
#define I2C2_SDA PB11
65+
66+
#define USE_BARO
67+
#define BARO_I2C_BUS BUS_I2C2
68+
#define USE_BARO_BMP280
69+
#define USE_BARO_DPS310
70+
#define USE_BARO_MS5611
71+
72+
#define USE_MAG
73+
#define MAG_I2C_BUS BUS_I2C2
74+
#define USE_MAG_HMC5883
75+
#define USE_MAG_QMC5883
76+
#define USE_MAG_IST8310
77+
#define USE_MAG_IST8308
78+
#define USE_MAG_MAG3110
79+
#define USE_MAG_LIS3MDL
80+
81+
#define TEMPERATURE_I2C_BUS BUS_I2C2
82+
83+
#define PITOT_I2C_BUS BUS_I2C2
84+
85+
#define USE_RANGEFINDER
86+
#define RANGEFINDER_I2C_BUS BUS_I2C2
87+
#define BNO055_I2C_BUS BUS_I2C2
88+
89+
// *************** FLASH **************************
90+
#define USE_SDCARD
91+
#define USE_SDCARD_SPI
92+
#define SDCARD_SPI_BUS BUS_SPI3
93+
#define SDCARD_CS_PIN PB9
94+
95+
96+
#define USE_SPI_DEVICE_3
97+
#define SPI3_SCK_PIN PB3
98+
#define SPI3_MISO_PIN PB4
99+
#define SPI3_MOSI_PIN PB5
100+
101+
102+
// ************PINIO to disable BT*****************
103+
#define USE_PINIO
104+
#define USE_PINIOBOX
105+
#define PINIO1_PIN PC13
106+
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
107+
108+
109+
// ************PINIO to other
110+
#define PINIO2_PIN PC14 //Enable vsw
111+
#define PINIO3_PIN PB8
112+
113+
114+
// *************** OSD *****************************
115+
#define USE_SPI_DEVICE_2
116+
#define SPI2_SCK_PIN PB13
117+
#define SPI2_MISO_PIN PB14
118+
#define SPI2_MOSI_PIN PB15
119+
120+
#define USE_MAX7456
121+
#define MAX7456_SPI_BUS BUS_SPI2
122+
#define MAX7456_CS_PIN PB12
123+
124+
// *************** UART *****************************
125+
#define USE_VCP
126+
127+
#define USE_UART1
128+
#define UART1_RX_PIN PA10
129+
#define UART1_TX_PIN PA9
130+
131+
#define USE_UART2
132+
#define UART2_RX_PIN PA3
133+
#define UART2_TX_PIN PA2
134+
135+
#define USE_UART4
136+
#define UART4_RX_PIN PC11
137+
#define UART4_TX_PIN PC10
138+
139+
#define USE_UART5
140+
#define UART5_RX_PIN PD2
141+
#define UART5_TX_PIN PC12
142+
143+
#define USE_UART6
144+
#define UART6_RX_PIN PC7
145+
#define UART6_TX_PIN PC6
146+
147+
#define SERIAL_PORT_COUNT 6
148+
149+
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
150+
#define SERIALRX_PROVIDER SERIALRX_SBUS
151+
#define SERIALRX_UART SERIAL_PORT_USART2
152+
153+
// *************** ADC *****************************
154+
#define USE_ADC
155+
#define ADC_INSTANCE ADC1
156+
#define ADC1_DMA_STREAM DMA2_Stream0
157+
#define ADC_CHANNEL_1_PIN PC1
158+
#define ADC_CHANNEL_2_PIN PC2
159+
#define ADC_CHANNEL_3_PIN PC0
160+
161+
#define VBAT_ADC_CHANNEL ADC_CHN_1
162+
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
163+
#define RSSI_ADC_CHANNEL ADC_CHN_3
164+
165+
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
166+
167+
#define USE_LED_STRIP
168+
#define WS2811_PIN PA1
169+
170+
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
171+
172+
#define TARGET_IO_PORTA 0xffff
173+
#define TARGET_IO_PORTB 0xffff
174+
#define TARGET_IO_PORTC 0xffff
175+
#define TARGET_IO_PORTD (BIT(2))
176+
177+
#define MAX_PWM_OUTPUT_PORTS 8
178+
179+
#define USE_DSHOT
180+
#define USE_ESC_SENSOR

0 commit comments

Comments
 (0)