Skip to content

Commit c8dba70

Browse files
committed
Merge branch '3.5.x-maintenance' into 3.5.x-Performance-Edition
2 parents 3668338 + 8da564a commit c8dba70

File tree

9 files changed

+399
-2
lines changed

9 files changed

+399
-2
lines changed
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
# Board - MATEKSYS F722-SE
2+
3+
Full details on the MATEKSYS F722-SE can be found on the Matek Website: [mateksys.com/?portfolio=f722-se](http://www.mateksys.com/?portfolio=f722-se). Betaflight Target: `MATEKF722SE`
4+
5+
## Hardware Specs
6+
7+
* *Mass:* ~10g
8+
* *PCB Size:* 36x46mm
9+
* 30x30mm Hole pattern (M4 size, M3 size with rubber isolators)
10+
11+
### FC Specs
12+
13+
* Processors and Sensors
14+
* *MCU:* STM32F722RET6
15+
* *IMU:* MPU6000(Gyro1) & ICM20602(Gyro2) connected via SPI1
16+
* *Baro:* BMP280 (connected via I2C1)
17+
* *OSD:* BetaFlight OSD (AT7456E connected via SPI2)
18+
* *Blackbox:* MicroSD card slot (connected via SPI3)
19+
* 5 UARTs (1,2,3,4,6)
20+
* 8 Dshot outputs
21+
* 2 PINIO (VTX power switcher/user1 and 2 camera switcher/user2)
22+
23+
### Integrated PDB Specs
24+
25+
* *Input:* 6-36v (3-8S LiPo)
26+
* *ESC Pads:* Rated 4x35A per ESC pad set (4x46A burst)
27+
* Voltage Regulators:
28+
* *5v BEC:* 2A continuous load (3A burst)
29+
* *3.3v LDO:* max load: 200mA
30+
* Power Sense:
31+
* *Current Sensor:* Rated for 184A (*Suggested scale value `179`*)
32+
* *Voltage Sensor:* 1:10 signal output ratio (*Suggested scale value `110`*)
33+
34+
## Status LEDs
35+
36+
| LED | Color | Color Codes |
37+
|---------------:|-------|:----------------------------------------------------------------------------------------------------------|
38+
| LED0 | Blue | FC Status |
39+
| LED1 | Green | FC Status |
40+
| LED3.3 | Red | 3v3 Status |
41+
42+
## Pinout
43+
44+
Pads are organised into two large banks of pads on left and right sides of board with a couple sets of pads on the underside of the board and ESC related connections near the board corners.
45+
46+
```
47+
__________
48+
/ U U \
49+
/-----------------------------\
50+
|oE Eo|
51+
|SC SC|
52+
| |
53+
| P P |
54+
| A A |
55+
| D D |
56+
| S S |
57+
| |
58+
|ES ES|
59+
|oC Co|
60+
\------------[USB]------------/
61+
```
62+
63+
64+
| Pad Silkscreen Label | Function | Notes |
65+
|---------------------:|---------------|:-----------------------------------------------------------------------------------------------|
66+
| `+ / -` | Battery In | 6-36vDC LiPo Power input (*Battery +/- and 4-in-1 ESC +/- pads*) |
67+
| `S1-S8` | ESC Out | (*1-4 near ESC power connections, 5-8 on right side*) Supports PWM, Oneshot, Multishot, DSHOT |
68+
| `GND, S1-S4` | ESC Out | (*Rear of board*) 4-in-1 ESC Out |
69+
| `VBat GND` | VBAT Out | VBAT power pad (*marked for VTX*), power ON/OFF can be switched via PINIO1(PC8) |
70+
| `CURR` | Current Sense | Current Sensor I/O pin (*output from onboard sensor or input from external sensor*) |
71+
| `5V` | | Out from internal 5v BEC (*rated 2A continuous, 3A burst*) |
72+
| `3V3` | | Out from 3v3 regulator (*rated 200mA*) |
73+
| `4V5` | | Out from 4v4~4v8, 0.5A (*power is also supplied when connected via USB*) |
74+
| `G` | GND | |
75+
| `LED` | WS2812 Signal | |
76+
| `Bz-, 5V` | Buzzer | |
77+
| `CL, DA` | I2C1 | I2C connection marked for a magnetometer but could be used for whatever |
78+
| `VTX` | VTX | VTX: Video out |
79+
| `C1/C2` | Camera | C1: camera-1 IN, C1: camera-2 IN, 2 camera video can be switched via PINIO2(PC9) |
80+
| `RX1, TX1` | UART1 | |
81+
| `TX2` | UART2-TX | |
82+
| `RX2` | UART2-RX | RX connection for Spektrum DSMX or DSM2, FlySky iBUS, or PPM (*Disable `UART2` for PPM*) |
83+
| `RX3, TX3` | UART3 | TX3 can be used for VTX control |
84+
| `RX4, TX4` | UART4 | RX4 pin `PA1` can be remapped for camera control(PWM) |
85+
| `TX6` | UART6-TX | |
86+
| `RX6` | UART6-RX | (*One per board corner*) Duplicates of RX6 pad for ESC Telemetry |
87+
| `Rssi` | RSSI | FrSky RSSI input from RX (*Rear of board*) |
88+
| `PA4 ` | ADC/DAC | EXTERNAL1_ADC_PIN (*Rear of board*) |
89+
| `D+, D-. VBus` | USB pins | (*Rear of board*) |
90+
91+

docs/boards/Board - SKYZONEF405.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ Standard 30 * 30 mm size
2626
Type|Description
2727
---|---
2828
MCU|STM32F405
29-
IMU|ICM-20689
29+
IMU|available with MPU6000 or ICM-20689
3030
IMU Interrupt|yes
3131
Motor outputs|up to 8
3232
Barometer|optional

src/main/interface/cli.c

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2561,7 +2561,10 @@ static void printMap(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfi
25612561
buf[i] = '\0';
25622562

25632563
const char *formatMap = "map %s";
2564-
cliDefaultPrintLinef(dumpMask, equalsDefault, formatMap, bufDefault);
2564+
if (defaultRxConfig) {
2565+
bufDefault[i] = '\0';
2566+
cliDefaultPrintLinef(dumpMask, equalsDefault, formatMap, bufDefault);
2567+
}
25652568
cliDumpPrintLinef(dumpMask, equalsDefault, formatMap, buf);
25662569
}
25672570

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
/*
2+
* This file is part of Cleanflight and Betaflight.
3+
*
4+
* Cleanflight and Betaflight are free software. You can redistribute
5+
* this software and/or modify this software under the terms of the
6+
* GNU General Public License as published by the Free Software
7+
* Foundation, either version 3 of the License, or (at your option)
8+
* any later version.
9+
*
10+
* Cleanflight and Betaflight are distributed in the hope that they
11+
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
12+
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13+
* See the GNU General Public License for more details.
14+
*
15+
* You should have received a copy of the GNU General Public License
16+
* along with this software.
17+
*
18+
* If not, see <http://www.gnu.org/licenses/>.
19+
*/
20+
21+
#include <stdint.h>
22+
23+
#include "platform.h"
24+
#include "io/serial.h"
25+
//#include "pg/pinio.h"
26+
#include "pg/piniobox.h"
27+
#include "target.h"
28+
29+
#define USE_TARGET_CONFIG
30+
31+
void targetConfiguration(void)
32+
{
33+
pinioBoxConfigMutable()->permanentId[0] = 40;
34+
pinioBoxConfigMutable()->permanentId[1] = 41;
35+
36+
}
37+
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
/*
2+
* This file is part of Cleanflight and Betaflight.
3+
*
4+
* Cleanflight and Betaflight are free software. You can redistribute
5+
* this software and/or modify this software under the terms of the
6+
* GNU General Public License as published by the Free Software
7+
* Foundation, either version 3 of the License, or (at your option)
8+
* any later version.
9+
*
10+
* Cleanflight and Betaflight are distributed in the hope that they
11+
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
12+
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13+
* See the GNU General Public License for more details.
14+
*
15+
* You should have received a copy of the GNU General Public License
16+
* along with this software.
17+
*
18+
* If not, see <http://www.gnu.org/licenses/>.
19+
*/
20+
21+
#include <stdint.h>
22+
23+
#include "platform.h"
24+
#include "drivers/io.h"
25+
26+
#include "drivers/dma.h"
27+
#include "drivers/timer.h"
28+
#include "drivers/timer_def.h"
29+
30+
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
31+
32+
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1 UP1-2
33+
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S2 UP1-2
34+
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S3 UP1-2
35+
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4 UP1-2
36+
37+
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // S5 UP1-7
38+
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // S6 UP1-7
39+
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // S7 UP1-6
40+
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // S8 UP1-6
41+
42+
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED DMA2-3
43+
44+
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2
45+
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // TX2
46+
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // RX4
47+
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // TX4
48+
49+
};
Lines changed: 195 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,195 @@
1+
/*
2+
* This file is part of Cleanflight and Betaflight.
3+
*
4+
* Cleanflight and Betaflight are free software. You can redistribute
5+
* this software and/or modify this software under the terms of the
6+
* GNU General Public License as published by the Free Software
7+
* Foundation, either version 3 of the License, or (at your option)
8+
* any later version.
9+
*
10+
* Cleanflight and Betaflight are distributed in the hope that they
11+
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
12+
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13+
* See the GNU General Public License for more details.
14+
*
15+
* You should have received a copy of the GNU General Public License
16+
* along with this software.
17+
*
18+
* If not, see <http://www.gnu.org/licenses/>.
19+
*/
20+
21+
#pragma once
22+
23+
#define USE_TARGET_CONFIG
24+
25+
#define TARGET_BOARD_IDENTIFIER "MF7S"
26+
#define USBD_PRODUCT_STRING "MATEKF722SE"
27+
28+
#define ENABLE_DSHOT_DMAR true
29+
30+
#define LED0_PIN PA14 //Blue SWCLK
31+
#define LED1_PIN PA13 //Green SWDIO
32+
33+
#define USE_BEEPER
34+
#define BEEPER_PIN PC13
35+
#define BEEPER_INVERTED
36+
37+
// *************** SPI1 Gyro & ACC *******************
38+
39+
#define USE_SPI
40+
#define USE_SPI_DEVICE_1
41+
#define SPI1_SCK_PIN PA5
42+
#define SPI1_MISO_PIN PA6
43+
#define SPI1_MOSI_PIN PA7
44+
45+
#define USE_DUAL_GYRO
46+
#define USE_EXTI
47+
#define GYRO_1_EXTI_PIN PC4
48+
#define GYRO_2_EXTI_PIN PC3
49+
#define MPU_INT_EXTI
50+
51+
#define GYRO_1_CS_PIN PB2
52+
#define GYRO_1_SPI_INSTANCE SPI1
53+
#define GYRO_2_CS_PIN PC15
54+
#define GYRO_2_SPI_INSTANCE SPI1
55+
56+
#define USE_GYRO
57+
#define USE_GYRO_SPI_MPU6000
58+
#define USE_GYRO_SPI_MPU6500
59+
60+
#define USE_ACC
61+
#define USE_ACC_SPI_MPU6000
62+
#define USE_ACC_SPI_MPU6500
63+
64+
#define GYRO_MPU6000_1_ALIGN CW180_DEG_FLIP
65+
#define ACC_MPU6000_1_ALIGN CW180_DEG_FLIP
66+
#define GYRO_1_ALIGN GYRO_MPU6000_1_ALIGN
67+
#define ACC_1_ALIGN ACC_MPU6000_1_ALIGN
68+
69+
#define GYRO_MPU6500_2_ALIGN CW90_DEG
70+
#define ACC_MPU6500_2_ALIGN CW90_DEG
71+
#define GYRO_2_ALIGN GYRO_MPU6500_2_ALIGN
72+
#define ACC_2_ALIGN ACC_MPU6500_2_ALIGN
73+
74+
#define USE_MPU_DATA_READY_SIGNAL
75+
#define ENSURE_MPU_DATA_READY_IS_LOW
76+
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
77+
78+
// *************** I2C /Baro/Mag *********************
79+
80+
#define USE_I2C
81+
82+
#define USE_I2C_DEVICE_1
83+
#define I2C_DEVICE_1 (I2CDEV_1)
84+
#define I2C1_SCL PB8
85+
#define I2C1_SDA PB9
86+
87+
#define BARO_I2C_INSTANCE (I2CDEV_1)
88+
#define USE_BARO
89+
#define USE_BARO_BMP280
90+
#define USE_BARO_MS5611
91+
#define USE_BARO_BMP085
92+
93+
#define MAG_I2C_INSTANCE (I2CDEV_1)
94+
#define USE_MAG
95+
#define USE_MAG_HMC5883
96+
#define USE_MAG_QMC5883
97+
98+
// *************** SPI2 OSD ***********************
99+
100+
#define USE_SPI_DEVICE_2
101+
#define SPI2_SCK_PIN PB13
102+
#define SPI2_MISO_PIN PB14
103+
#define SPI2_MOSI_PIN PB15
104+
105+
#define USE_MAX7456
106+
#define MAX7456_SPI_INSTANCE SPI2
107+
#define MAX7456_SPI_CS_PIN PB12
108+
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD)
109+
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
110+
111+
// *************** SPI3 SD BLACKBOX****************
112+
113+
#define USE_SDCARD
114+
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
115+
116+
#define USE_SPI_DEVICE_3
117+
#define SPI3_SCK_PIN PC10
118+
#define SPI3_MISO_PIN PC11
119+
#define SPI3_MOSI_PIN PC12
120+
121+
#define SDCARD_SPI_INSTANCE SPI3
122+
#define SDCARD_SPI_CS_PIN PD2
123+
124+
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream5
125+
#define SDCARD_DMA_CHANNEL 0
126+
127+
// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
128+
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
129+
// Divide to under 25MHz for normal operation:
130+
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
131+
132+
// *************** UART *****************************
133+
134+
#define USE_VCP
135+
#define USB_DETECT_PIN PC14
136+
#define USE_USB_DETECT
137+
138+
#define USE_UART1
139+
#define UART1_TX_PIN PA9
140+
#define UART1_RX_PIN PA10
141+
142+
#define USE_UART2
143+
#define UART2_TX_PIN PA2
144+
#define UART2_RX_PIN PA3
145+
146+
#define USE_UART3
147+
#define UART3_TX_PIN PB10
148+
#define UART3_RX_PIN PB11
149+
150+
#define USE_UART4
151+
#define UART4_TX_PIN PA0
152+
#define UART4_RX_PIN PA1
153+
154+
#define USE_UART6
155+
#define UART6_TX_PIN PC6
156+
#define UART6_RX_PIN PC7
157+
158+
#define USE_SOFTSERIAL1
159+
160+
#define SERIAL_PORT_COUNT 7
161+
162+
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
163+
#define SERIALRX_PROVIDER SERIALRX_SBUS
164+
#define SERIALRX_UART SERIAL_PORT_USART2
165+
166+
// *************** ADC *****************************
167+
#define USE_ADC
168+
#define ADC1_DMA_STREAM DMA2_Stream0
169+
#define VBAT_ADC_PIN PC2
170+
#define CURRENT_METER_ADC_PIN PC1
171+
#define RSSI_ADC_PIN PC0
172+
#define EXTERNAL1_ADC_PIN PA4
173+
174+
// *************** Others ***************************
175+
176+
#define USE_PINIO
177+
#define PINIO1_PIN PC8 // VTX power switcher
178+
#define PINIO2_PIN PC9 // 2xCamera switcher
179+
#define USE_PINIOBOX
180+
181+
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY )
182+
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
183+
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
184+
#define CURRENT_METER_SCALE_DEFAULT 179
185+
186+
#define USE_ESCSERIAL
187+
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
188+
189+
#define TARGET_IO_PORTA 0xffff
190+
#define TARGET_IO_PORTB 0xffff
191+
#define TARGET_IO_PORTC 0xffff
192+
#define TARGET_IO_PORTD 0xffff
193+
194+
#define USABLE_TIMER_CHANNEL_COUNT 13
195+
#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(9))

0 commit comments

Comments
 (0)