mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 01:05:21 +03:00
Merge branch 'master' into dzikuvx-rate-dynamics
This commit is contained in:
commit
ca91e42100
22 changed files with 74 additions and 1168 deletions
|
@ -1,88 +0,0 @@
|
|||
|
||||
## Connections
|
||||
|
||||
Board orientation.
|
||||
|
||||
These notes assume that when the board is placed with the header pins facing up, the bottom right of the board is next to the 8 sets of INPUT pin headers.
|
||||
Inner means between the two rows of header sockets, outer means between the left/right board edges and the header sockets.
|
||||
|
||||
|
||||
### SPI2 / External SPI
|
||||
|
||||
sclk GPIOB 13
|
||||
miso GPIOB 14
|
||||
mosi GPIOB 15
|
||||
|
||||
|
||||
There are 4 pins, labelled CS1-4 next to a label that reads Ext SPI. The 3rd pin is connected to the flash chip on
|
||||
the bottom right inner of the board. The other pins on the flash chip are wired up to PB3/4/5
|
||||
|
||||
### SPI3 / SPI
|
||||
|
||||
sclk GPIOB 3
|
||||
miso GPIOB 4
|
||||
mosi GPIOB 5
|
||||
|
||||
ssel 1 GPIOB 10 / Ext SPI CS1
|
||||
ssel 2 GPIOB 11 / Ext SPI CS2
|
||||
ssel 3 GPIOB 12 / Ext SPI CS3 - wired up to Slave Select of M25P16 15MBitFlash chip
|
||||
ssel 4 GPIOB 13 / Ext SPI CS4 - not usable since it is used for SPI2 sclk
|
||||
|
||||
### RC Input
|
||||
|
||||
INPUT
|
||||
PA8 / CH1 - TIM1_CH1
|
||||
PB8 / CH2 - TIM16_CH1
|
||||
PB9 / CH3 - TIM17_CH1
|
||||
PC6 / CH4 - TIM8_CH1
|
||||
PC7 / CH5 - TIM8_CH2
|
||||
PC8 / CH6 - TIM8_CH3
|
||||
PF9 / CH7 - TIM15_CH1
|
||||
PF10 / CH8 - TIM15_CH2
|
||||
|
||||
### PWM Outputs
|
||||
|
||||
OUTPUT
|
||||
PD12 / CH1 - TIM4_CH1
|
||||
PD13 / CH2 - TIM4_CH2
|
||||
PD14 / CH3 - TIM4_CH3
|
||||
PD15 / CH4 - TIM4_CH4
|
||||
PA1 / CH5 - TIM2_CH2
|
||||
PA2 / CH6 - TIM2_CH3
|
||||
PA3 / CH7 - TIM2_CH4
|
||||
PB0 / CH8 - TIM3_CH3
|
||||
PB1 / CH9 - TIM3_CH4
|
||||
PA4 / CH10 - TIM3_CH2
|
||||
|
||||
### Other ports
|
||||
|
||||
There is space for a MS5611 pressure sensor at the top left inner of the board.
|
||||
|
||||
There is an I2C socket on the left outer of the board which connects to a PCA9306 I2C level shifter directly opposite (inner).
|
||||
The PCA9306 is not populated on some boards and thus the I2C socket is unusable.
|
||||
|
||||
There is a CAN socket on the top right outer of the board which connects to a MAX3015 CAN Tranceiver.
|
||||
The MAX3015 is not populated on some boards and thus the CAN socket is unusable.
|
||||
|
||||
There are some solder pads labelled Ext 1-4 at the top right inner of the board.
|
||||
|
||||
GPIOE 6 / PE6 / Ext 1
|
||||
GPIOD 3 / PD3 / Ext 2
|
||||
GPIOD 4 / PD4 / Ext 3
|
||||
GPIOB 3 / PB3 / Ext 4
|
||||
|
||||
There are some solder pads labelled ADC0-3 & Diff Press at the top left inner of the board
|
||||
They are connected to the ADC socket at the top left outer of the board
|
||||
|
||||
PC3 / Diff Press - ADC12_IN9 (Differential Pressure)
|
||||
PC2 / ADC2 - ADC12_IN8
|
||||
PC1 / ADC1 - ADC12_IN7
|
||||
PC0 / ADC0 - ADC12_IN6
|
||||
|
||||
There is space for a MPXV5004/MPVZ5004 differential pressure sensor, if populated it's analog pin connects to PC3.
|
||||
|
||||
There are sockets for 5 UARTs labelled USART1-5.
|
||||
|
||||
There is a socket labelled RX_IN.
|
||||
|
||||
GPIOD 2 / PD2 / RX_IN
|
|
@ -1,126 +0,0 @@
|
|||
# Board - Colibri RACE
|
||||
|
||||
The Colibri RACE is a STM32F3 based flight control designed specifically to work with the TBS POWERCUBE multi rotor stack.
|
||||
|
||||
## Hardware Features:
|
||||
* STM32F303 based chipset for ultimate performance
|
||||
* PPM, SBUS, DSM, DSMX input (5V and 3.3V provided over internal BUS). No inverters or hacks needed.
|
||||
* 6 PWM ESC output channels (autoconnect, internal BUS)
|
||||
* RGB LED strip support incl. power management
|
||||
* Extension port for GPS / external compass / pressure sensor
|
||||
* UART port for peripherals (Blackbox, FrSky telemetry etc.)
|
||||
* Choose between plug & play sockets or solder pads for R/C and buzzer
|
||||
* 5V buzzer output
|
||||
* MPU6500 new generation accelerometer/gyro
|
||||
* 3x status LED (DCDC pwr/ 3.3V pwr/ status)
|
||||
* Battery monitoring for 12V, 5V and VBat supply
|
||||
* Size: 36mmx36mm (30.5mm standard raster)
|
||||
* Weight: 4.4g
|
||||
|
||||
For more details please visit:
|
||||
http://www.team-blacksheep.com/powercube
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | Board Markings | Notes |
|
||||
| ----- | ------------ | -------------- | ------------------------------------------|
|
||||
| 1 | VCP | USB PORT | Main Port For MSP |
|
||||
| 2 | USART1 | FREE PORT | PC4 and PC5(Tx and Rx respectively) |
|
||||
| 3 | USART2 | PPM Serial | PA15 |
|
||||
| 4 | USART3 | GPS PORT | PB10 and PB11(Tx and Rx respectively) |
|
||||
|
||||
## Pinouts
|
||||
|
||||
Full pinout details are available in the manual, here:
|
||||
|
||||
http://www.team-blacksheep.com/colibri_race
|
||||
|
||||
|
||||
### SWD - ICSP
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | VCC_IN | 3.3 Volt |
|
||||
| 2 | SWDIO | |
|
||||
| 3 | nRESET | |
|
||||
| 4 | SWCLK | |
|
||||
| 5 | Ground | |
|
||||
| 6 | SWO/TDO | |
|
||||
|
||||
### Internal Bus
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | PWM1 | MOTOR 1 |
|
||||
| 2 | PWM2 | MOTOR 2 |
|
||||
| 3 | PWM3 | MOTOR 3 |
|
||||
| 4 | PWM4 | MOTOR 4 |
|
||||
| 5 | PWM5 | MOTOR 5 (For Y6 or Hex X) |
|
||||
| 6 | PWM6 | MOTOR 6 (For Y6 or Hex X) |
|
||||
| 7 | BST SDA | Use For TBS CorePro Control Device |
|
||||
| 8 | BST SCL | Use For TBS CorePro Control Device |
|
||||
| 9 | PWM7 | Can be a normal GPIO (PA1) or PWM |
|
||||
| 10 | PWM8 | Can be a normal GPIO (PA2) or PWM |
|
||||
| 11 | 12.2V DCDC | If 12v is detected, the Blue LED will turn on|
|
||||
| 12 | 5.1V DCDC | Voltage for MCU |
|
||||
|
||||
### Servo
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_OUT | 5.1 Volt output to LCD Strip |
|
||||
| 3 | PWM Servo | PB14 - PWM10 |
|
||||
|
||||
### IO_1 - LED Strip
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | LED_STRIP | Enable `feature LED_STRIP` |
|
||||
| 2 | VCC_OUT | 5.1 Volt output to LCD Strip |
|
||||
| 3 | Ground | |
|
||||
|
||||
### IO_2 - Sensor Interface
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | VCC_OUT | 4.7 Volt output to the device |
|
||||
| 2 | Ground | |
|
||||
| 3 | UART3 TX | GPS |
|
||||
| 4 | UART3 RX | GPS |
|
||||
| 5 | SDA | mag, pressure, or other i2c device |
|
||||
| 6 | SCL | mag, pressure, or other i2c device |
|
||||
|
||||
### IO_3 - RC input
|
||||
|
||||
IO_3 is used for RX_PPM/RX_SERIAL. Under the `PORT` tab, set RX_SERIAL to UART2 when using RX_SERIAL.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | PPM/Serial | Can PPM or Serial input |
|
||||
| 2 | VCC_OUT | 3.3 Volt output to the device |
|
||||
| 3 | Ground | |
|
||||
| 4 | VCC_OUT | 5.1 Volt output to the device |
|
||||
|
||||
### IO_4 - Buzzer
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | BUZZER | Normal high (5.1v) |
|
||||
| 2 | VCC_OUT | 5.1 Volt output to the device |
|
||||
|
||||
### IO_5 - Free UART
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | UART1 TX | Free UART |
|
||||
| 2 | UART1 RX | Free UART |
|
||||
| 3 | Ground | |
|
||||
| 4 | VCC_OUT | 4.7 Volt output to the device |
|
||||
|
||||
### IO_6 - IR TX (extension)
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ----------------- | -------------------------------------------- |
|
||||
| 1 | IR TX | |
|
||||
| 2 | Ground | |
|
|
@ -1,101 +0,0 @@
|
|||
# Board - MotoLab
|
||||
|
||||
The MOTOLAB build target supports the STM32F3-based boards provided by MotoLab.
|
||||
|
||||
At present this includes the TornadoFC and MotoF3. The TornadoFC is described here:
|
||||
|
||||
http://www.rcgroups.com/forums/showthread.php?t=2473157
|
||||
|
||||
The MotoF3 documentation will be provided when the board is available.
|
||||
|
||||
Both boards use the STM32F303 microcontroller and have the following features:
|
||||
|
||||
* 256K bytes of flash memory
|
||||
* Floating point math coprocessor
|
||||
* Three hardware serial port UARTs
|
||||
* USB using the built-in USB phy that does not interfere with any hadware UART
|
||||
* Stable voltage regulation
|
||||
* High-current buzzer/LED output
|
||||
* Serial LED interface
|
||||
* Low-pass filtered VBAT input with 1/10 divider ratio
|
||||
* 8 short-circuit protected PWM outputs, with 5V buffering on the TornadoFC
|
||||
* On-board 6S-compatible switching regulator (MotoF3)
|
||||
* Direct mounting option for a Pololu switching regulator for up to 6S lipo operation (TornadoFC)
|
||||
|
||||
|
||||
# Flashing
|
||||
|
||||
The MotoLab boards use the internal DFU USB interface on the STM32F3 microcontroller which is not compatible with the INAV configurator flashing tool.
|
||||
|
||||
Instead, on Windows you can use the Impulse Flashing Utility from ImpulseRC, available here:
|
||||
|
||||
http://www.warpquad.com/ImpulseFlash.zip
|
||||
|
||||
Download and unzip the program. Start the program, plug in the USB on the target board, and drag and drop the intended binary file onto the program icon. The program will put the STM32F3 into bootloader mode automatically and load the binary file to the flash.
|
||||
|
||||
For programming on Linux, use the dfu-util program which is installed by default on Ubuntu-based systems. Connect the boot pins on the board and plug in the USB.
|
||||
|
||||
Verify that the system identifies the DFU device with this command:
|
||||
```
|
||||
dfu-util -l
|
||||
```
|
||||
|
||||
The output should list a "Found DFU" device, something like this:
|
||||
```
|
||||
dfu-util 0.5
|
||||
|
||||
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
|
||||
(C) 2010-2011 Tormod Volden (DfuSe support)
|
||||
This program is Free Software and has ABSOLUTELY NO WARRANTY
|
||||
|
||||
dfu-util does currently only support DFU version 1.0
|
||||
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
|
||||
```
|
||||
|
||||
Use this command to load the binary file to the flash memory on the board:
|
||||
```
|
||||
dfu-util --alt 0 -s 0x08000000 -D <binfile>
|
||||
```
|
||||
|
||||
The output should look something like this:
|
||||
```
|
||||
dfu-util 0.5
|
||||
|
||||
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
|
||||
(C) 2010-2011 Tormod Volden (DfuSe support)
|
||||
This program is Free Software and has ABSOLUTELY NO WARRANTY
|
||||
|
||||
dfu-util does currently only support DFU version 1.0
|
||||
|
||||
Opening DFU USB device... ID 0483:df11
|
||||
Run-time device DFU version 011a
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
|
||||
Claiming USB DFU Interface...
|
||||
Setting Alternate Setting #0 ...
|
||||
Determining device status: state = dfuDNLOAD-IDLE, status = 0
|
||||
aborting previous incomplete transfer
|
||||
Determining device status: state = dfuIDLE, status = 0
|
||||
dfuIDLE, continuing
|
||||
DFU mode device DFU version 011a
|
||||
Device returned transfer size 2048
|
||||
No valid DFU suffix signature
|
||||
Warning: File has no DFU suffix
|
||||
DfuSe interface name: "Internal Flash "
|
||||
```
|
||||
|
||||
A binary file is required for the Impulse flashing Utility and dfu-util. The binary file can be built as follows:
|
||||
```
|
||||
make TARGET=MOTOLAB clean
|
||||
make TARGET=MOTOLAB binary
|
||||
```
|
||||
|
||||
To completely erase the flash, create an all-zero file with this command on linux:
|
||||
```
|
||||
dd if=/dev/zero of=zero.bin bs=1 count=262144
|
||||
```
|
||||
|
||||
## Todo
|
||||
|
||||
Pinout documentation
|
|
@ -1,87 +0,0 @@
|
|||
# Board - OMNIBUS F3
|
||||
|
||||
> This board is not supported in recent INAV releases
|
||||
|
||||
## Hardware Features
|
||||
|
||||
Refer to the product web page:
|
||||
[OMNIBUS AIO F3 Flight Control](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusv11.html)
|
||||
|
||||
### Hardware Notes
|
||||
|
||||
There are few things to note on how things are connected on the board.
|
||||
|
||||
1. VBAT (J4)
|
||||
This is a battery input to the board, and is also a input to voltage sensor.
|
||||
|
||||
2. J11 Power distribution
|
||||
The RAM is user defined power rail, and all RAM through holes (J6, J7 and J11) are connected together. By connecting 5V or VBAT to RAM at J11, the RAM becomes 5V or VBAT power rail respectively. The VBAT on J11 can also be used to power the Board if necessary.
|
||||
|
||||
3. RSSI (J4)
|
||||
The pin is labelled as RSSI, but it will not be used for RSSI input for a hardware configuration limitation. In this document, the "RSSI" is used to indicate the pin location, not the function.
|
||||
|
||||
4. UART1 in boot-loader/DFU mode
|
||||
The UART1 is scanned during boot-loader/DFU mode, together with USB for possible interaction with a host PC. It is observed that devices that autonomously transmits some data, such as GPS, will prevent the MCU to talk to the USB. It is advised not to connect or disconnect such devices to/from UART1. UART2 is safe from this catch.
|
||||
|
||||
## iNav Specific Target Configuration
|
||||
|
||||
The first support for the OMNIBUS F3 appeared in BetaFlight.
|
||||
The OMNIBUS target in iNav has different configuration from the BetaFlight support, to maximize the hardware resource utilization for navigation oriented use cases.
|
||||
|
||||
[PIN CONFIGURATION PIC HERE]
|
||||
|
||||
### PWM Outputs
|
||||
|
||||
Six PWM outputs (PWM1~PWM6) are supported, but PWM5 and PWM6 is not available when UART3 is in use.
|
||||
PWM7 and PWM8 are dedicated for I2C; in this document, they are used to indicate the pin location, not the function.
|
||||
|
||||
If servos are used on a multirotor mixer (i.e. Tricopter) PWM1 is remapped to servo and motor 1 is moved to PWM2 etc.
|
||||
|
||||
Note: Tested only for QUAD-X configuration.
|
||||
|
||||
### Hardware UART Ports
|
||||
|
||||
PPM/SBUS jumper for J8 is assumed to be configured for PPM (SBUS=R18 removed). With newer boards (the 1.1 Version) you don't have to swap an smd resistor to use SBUS anymore. It just works out of the box.
|
||||
|
||||
| UART | Location | Note |
|
||||
|-------|----------|-------------------|
|
||||
| UART1 |J13 | |
|
||||
| UART2 |J12 | |
|
||||
| UART3 |J22 | PWM5=TX3,PWM6=RX3 |
|
||||
|
||||
All UARTs are Serial RX capable.
|
||||
|
||||
### I2C
|
||||
|
||||
I2C is available on J22 PWM7 and PWM8
|
||||
|
||||
|signal | Location | Alt. Location |
|
||||
|-------|------------|---------------|
|
||||
|SCL | J22 (PWM8) | J3 (SCL) |
|
||||
|SDA | J22 (PWM7) | J3 (SDA) |
|
||||
|
||||
### RANGEFINDER
|
||||
|
||||
HC-SR04 rangefinder is supported when NOT using PPM.
|
||||
|
||||
|signal | Location |
|
||||
|-------|------------|
|
||||
|TRIG | J8 (PPM) |
|
||||
|ECHO | J4 (RSSI) |
|
||||
|
||||
5V rangefinder can be connected directly without inline resistors.
|
||||
|
||||
### OSD
|
||||
|
||||
Integrated OSD is supported.
|
||||
|
||||
### RSSI Sensor Input
|
||||
|
||||
The RSSI sensor adc is not supported due to the hardware configuration limitation.
|
||||
|
||||
## Usage in a Fixed Wing
|
||||
Due to the way INAV handles PWM outputs the first 2 PWM outputs are reserved for the motor outputs. When using SBUS on UART3 as recommended this leaves only 2 additional outputs for the servos, as output 5 and 6 are blocked by UART3 serial for SBUS and 7 and 8 are used for I2C.
|
||||
|
||||
You can free PWM outputs 5 and 6 by simply connecting SBUS up to UART1. For FrSky there is no hardware inverter needed as the F3 chip UARTs can handle this without additional hardware. Just make sure that `sbus_inversion = ON` is set. However, you will not be able to use UART3, e.G. for telemetry.
|
||||
|
||||
This allows to control a standard airplane with rudder, ailerons and elevator. If you use flaps or a servo gimbal, you can bypass the FC by connecting it up to the receiver directly.
|
|
@ -1,46 +0,0 @@
|
|||
# Board - Paris Air Hero 32
|
||||
|
||||
This is the AIR3 PARIS Sirius AirHERO 32 F3 board from MultiWiiCopter
|
||||
Source: http://www.multiwiicopter.com/products/inav-air3-fixed-wing
|
||||
|
||||
## Sensors
|
||||
|
||||
MPU6500 via SPI interface.
|
||||
BMP280 via SPI interface
|
||||
|
||||
## Ports
|
||||
|
||||
6 x 3pin ESC / Servo outputs
|
||||
1 x 8pin JST connector (PPM/PWM/UART2)
|
||||
1 x 4pin JST connector (UART3)
|
||||
|
||||
## I2C bus
|
||||
|
||||
I2C bus is made available with a special target - AIRHEROF3_QUAD. This target limits motor outputs to 4 and adds I2C bus at M5/M6 connectors.
|
||||
|
||||
## Pinouts
|
||||
|
||||
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
|
||||
|
||||
From right to left when looking at the socket from the edge of the board.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | +5V | |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | AIRSPEED | Airspeed sensor (3.3V max) |
|
||||
| 5 | USART2 TX | |
|
||||
| 6 | USART2 RX | |
|
||||
| 7 | SS1 RX | Enable `feature SOFT_SERIAL` |
|
||||
| 8 | SS1 TX | |
|
||||
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | Notes |
|
||||
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | RX / PA10 | TX / PA9 | Internally connected to USB port via CP2102 IC |
|
||||
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
|
||||
| 3 | USART3 | F3 / PB11 | F2 / PB10 | |
|
||||
|
|
@ -1,46 +0,0 @@
|
|||
# Board - Paris Air Hero 32
|
||||
|
||||
## Sensors
|
||||
|
||||
MPU6500 via SPI interface.
|
||||
|
||||
## Ports
|
||||
|
||||
6 x 3pin ESC / Servo outputs
|
||||
1 x 8pin JST connector (PPM/PWM/UART2)
|
||||
1 x 4pin JST connector (UART3/I2C)
|
||||
|
||||
## Pinouts
|
||||
|
||||
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
|
||||
|
||||
From right to left when looking at the socket from the edge of the board.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | +5V | |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
|
||||
| 5 | USART2 TX | |
|
||||
| 6 | USART2 RX | Built-in inverter |
|
||||
| 7 | LED_STRIP | Enable `feature LED_STRIP` |
|
||||
| 8 | unused | |
|
||||
|
||||
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but one SoftSerial port is made available to use instead.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 7 | SOFTSERIAL1 RX | Enable `feature SOFTSERIAL` |
|
||||
| 8 | SOFTSERIAL1 TX | |
|
||||
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | Notes |
|
||||
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | RX / PA10 | TX / PA9 / TELEM | TELEM output is always inverted (for FrSky). Internally connected to USB port via CP2102 IC |
|
||||
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
|
||||
| 3 | USART3 | F3 / PB11 | F2 / PB10 | Flex port is configured as UART3 when port is configured |
|
||||
| 4 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |
|
||||
|
|
@ -1,12 +0,0 @@
|
|||
# Board - RMDO
|
||||
|
||||
The DoDo board is a clone of the SPRacingF3 board in terms of CPU pin mappings. See the SPRacingF3 documentation.
|
||||
|
||||
Hardware differences compared to SPRacingF3 are as follows:
|
||||
|
||||
* Rev 1 and Rev 2: the CPU is the cheaper version of the F3 with only 128KB FLASH. Rev 3: the CPU is a F3 version with 256KB FLASH.
|
||||
* 2MBit flash size
|
||||
* The barometer is the cheaper BMP280.
|
||||
* It does not have any compass sensor.
|
||||
* Onboard BEC.
|
||||
* Different physical connectors/pins/pads/ports.
|
|
@ -1,97 +0,0 @@
|
|||
# Board - SPRacingF3
|
||||
|
||||
The Seriously Pro Racing MOF3 board (SPRacingF3) is the first board designed specifically for INAV.
|
||||
|
||||
Full details available on the website, here:
|
||||
|
||||
http://seriouslypro.com/spracingf3
|
||||
|
||||
## Hardware Features
|
||||
|
||||
* No compromise I/O. Use all the features all the time; e.g. Connect your OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + HC-SR04 + 8 motors - all at the same time!
|
||||
* On-board high-capacity black box flight log recorder - optimize your tuning and see the results of your setup without guesswork. (Acro and Deluxe)
|
||||
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
|
||||
* Stackable design - perfect for integrating with OSDs and power distribution boards.
|
||||
* 16 PWM I/O lines for ESCs, Servos and legacy receivers. 8 available on standard pin headers. 8 via side mounted connectors.
|
||||
* Supports SBus, SumH, SumD, Spektrum1024/2048, XBus, PPM, PWM receivers. No external inverters required (built-in).
|
||||
* Dedicated output for programmable LEDs - great for orientation, racing and night flying.
|
||||
* Dedicated I2C port for connection of OLED display without needing flight battery.
|
||||
* Battery monitoring ports for voltage and current.
|
||||
* Buzzer port for audible warnings and notifications.
|
||||
* Solder pads in addition to connectors for HC-SR04, PPM, RSSI, Current, GPIO, LED Strip, 3.3v,
|
||||
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
|
||||
* Symmetrical design for a super tidy wiring.
|
||||
* Wire up using using pin headers, JST-SH sockets or solder pads. Use either right-angled or straight pin-headers.
|
||||
* Barometer mounted on the bottom of the board for easy wind isolation.
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
|
||||
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | PA10 | PA9 | YES | Internally connected to USB port via CP2102 IC. Also available on a USART1 JST connector and on through hole pins. |
|
||||
| 2 | USART2 | PA15 | PA14 | YES | Available on USART2 JST port only. |
|
||||
| 3 | USART3 | PB11 / IO2_3 | PB10 / IO2_4 | NO | Available on IO_2, USART3 JST port and through hole pins. |
|
||||
|
||||
* You cannot use SWD and USART2 at the same time.
|
||||
* You may encounter flashing problems if you have something connected to the USART1 RX/TX pins. Power other devices of and/or disconnect them.
|
||||
|
||||
## Pinouts
|
||||
|
||||
Full pinout details are available in the manual, here:
|
||||
|
||||
http://seriouslypro.com/spracingf3#manual
|
||||
|
||||
### IO_1
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | GPIO | |
|
||||
| 5 | SoftSerial1_RX | |
|
||||
| 6 | SoftSerial1_TX | |
|
||||
| 7 | LED_STRIP | Enable `feature LED_STRIP` |
|
||||
| 8 | VCC | 3.3v output for LOW CURRENT application only |
|
||||
|
||||
### IO_2
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ------------------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_SERIAL | UART3 RX |
|
||||
| 4 | | UART3_TX |
|
||||
| 5 | HC-SR04_TRIG/SoftSerial2_RX | Enable `feature SOFTSERIAL` or HC-SR04 rangefinder |
|
||||
| 6 | HC-SR04_ECHO/SoftSerial2_TX | Enable `feature SOFTSERIAL` or HC-SR04 rangefinder |
|
||||
| 7 | ADC_1 | Current Sensor |
|
||||
| 8 | ADC_2 | RSSI |
|
||||
|
||||
### UART1/2/3
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | TXD | |
|
||||
| 4 | RXD | |
|
||||
|
||||
### I2C
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
|
||||
| 3 | SCL | |
|
||||
| 4 | SDA | |
|
||||
|
||||
### SWD
|
||||
|
||||
The port cannot be used at the same time as UART2.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | NRST | Voltage as-supplied by BEC OR USB, always on |
|
||||
| 3 | SWDIO | |
|
||||
| 4 | SWDCLK | |
|
|
@ -1,160 +0,0 @@
|
|||
# Board - Seriously Pro SP Racing F3 EVO
|
||||
|
||||
The Seriously Pro Racing F3 Evo board (SPRacingF3EVO) is the evolution of the first board designed specifically for Cleanflight.
|
||||
|
||||
Purchasing boards directly from SeriouslyPro / SP Racing and official retailers helps fund Cleanflight development, it's the reason the Seriously Pro boards exist! Official retailers are always listed on the SeriouslyPro.com website.
|
||||
|
||||
Full details available on the website, here:
|
||||
|
||||
http://seriouslypro.com/spracingf3evo
|
||||
|
||||
## Hardware Features
|
||||
|
||||
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
|
||||
* MicroSD-Card socket for black box flight log recorder - optimize your tuning and see the results of your setup without guesswork.
|
||||
* Race transponder built in - just turn up at a race and have your lap times recorded.
|
||||
* Features the latest Accelerometer, Gyro and Mag/Compass and Baro/Altitude sensor technology.
|
||||
* Wire up using using pin headers for all major connections for excellent crash-durability. Use either right-angled or straight pin-headers.
|
||||
* No compromise I/O. Use all the features all the time; e.g. Connect your USB + OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + 8 motors - all at the same time!
|
||||
* 8 PWM output lines for ESCs and Servos. Arranged for easy wiring on standard pin headers.
|
||||
* Supports direct connection of SBus, SumH, SumD, Spektrum1024/2048, XBus receivers. No external inverters required (built-in).
|
||||
* Supports direct connection of 3.3v Spektrum Satellite receivers via 3 pin through-hole JST-ZH connector.
|
||||
* Dedicated PPM receiver input.
|
||||
* 3 Serial Ports - NOT shared with the USB socket.
|
||||
* Telemetry port
|
||||
* Micro USB socket.
|
||||
* Dedicated output for programmable LEDs - great for orientation, racing and night flying. (Currently mutually exclusive with the Transponder).
|
||||
* Dedicated I2C port for connection of OLED display without needing flight battery.
|
||||
* Battery monitoring for voltage and current.
|
||||
* RSSI monitoring (analogue or PWM).
|
||||
* Buzzer port for audible warnings and notifications.
|
||||
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
|
||||
* Symmetrical design for a super tidy wiring.
|
||||
* JST-SH sockets only for I2C, UART2 and SWD. UART2 also on through-hole pins.
|
||||
* Flashing via USB or serial port.
|
||||
* Stackable design - perfect for integrating with OSDs and power distribution boards.
|
||||
* Standard mounting - 36x36mm with standard 30.5mm mounting holes.
|
||||
* LEDs for 3v, 5v and Status for easy diagnostics.
|
||||
* Copper-etched Cleanflight logo.
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
|
||||
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | PA10 | PA9 | YES | 2 through-hole pins. Use for connecting to OSD/GPS/BlueTooth. |
|
||||
| 2 | USART2 | PA15 | PA14 / SWCLK | YES | JST socket and PPM header. Use to connect to RX. |
|
||||
| 3 | USART3 | PB11 / AF7 | PB10 / AF7 | NO | Available on 4 through-hole pins. 3.3V signals only ! Use for GPS, Spektrum Satellite RX, SmartPort Telemetry, HoTT telemetry, etc. |
|
||||
|
||||
* You cannot use SWD and USART2 at the same time.
|
||||
* When using a Serial RX receiver the TXD (T2) pin cannot be used for telemetry. Use UART3 TXD instead.
|
||||
* Two SoftSerial is supported. Enabling SoftSerial disables Servo output 3,4,5,6
|
||||
* Windows DFU Flashing requires Zadig (see configurator)
|
||||
|
||||
### SoftSerial
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 5 | SOFTSERIAL1 RX | SoftSerial replaces Servo 3,4,5,6|
|
||||
| 6 | SOFTSERIAL1 TX | |
|
||||
| 7 | SOFTSERIAL2 RX | |
|
||||
| 8 | SOFTSERIAL2 TX | |
|
||||
|
||||
|
||||
## Pinouts
|
||||
|
||||
Full pinout details are available in the manual, here:
|
||||
|
||||
http://seriouslypro.com/files/SPRacingF3EVO-Manual-latest.pdf
|
||||
|
||||
### IO_1
|
||||
|
||||
The 6 pin IO_1 connector has the following pinouts when used in RX_SERIAL mode.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_SERIAL | Enable `feature RX_SERIAL` |
|
||||
| 4 | | |
|
||||
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
|
||||
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
|
||||
|
||||
When RX_PPM is used the IO_1 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | TELEMETRY | Enable `feature TELEMETRY` |
|
||||
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
|
||||
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
|
||||
|
||||
### IO_2
|
||||
|
||||
When TRANSPONDER is used and the IR solder pads are shorted, the 6 pin IO_2 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ------------------------- | -------------------------------------------- |
|
||||
| 1 | IR- | Short leg of the IR LED |
|
||||
| 2 | IR+ | Long leg of the IR LED |
|
||||
| 3 | CURRENT | Current Sensor |
|
||||
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
|
||||
| 5 | BUZZER+ | 5V Source |
|
||||
| 6 | BUZZER- | Buzzer signal |
|
||||
|
||||
When LEDSTRIP is used and the LED solder pads are shorted, the 6 pin IO_2 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ------------------------- | -------------------------------------------- |
|
||||
| 1 | | |
|
||||
| 2 | LEDSTRIP | WS2812 Ledstrip data |
|
||||
| 3 | CURRENT | Current Sensor |
|
||||
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
|
||||
| 5 | BUZZER+ | 5V Source |
|
||||
| 6 | BUZZER- | Buzzer signal |
|
||||
|
||||
### UART1
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 3 | TXD | |
|
||||
| 4 | RXD | |
|
||||
|
||||
### UART2/3
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | TXD | |
|
||||
| 4 | RXD | |
|
||||
|
||||
### Spektrum Satellite
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 3 | 3.3V | |
|
||||
| 2 | Ground | |
|
||||
| 1 | RXD | |
|
||||
|
||||
### I2C
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
|
||||
| 3 | SCL | 3.3V signals only |
|
||||
| 4 | SDA | 3.3V signals only |
|
||||
|
||||
### SWD
|
||||
|
||||
The port cannot be used at the same time as UART2.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | NRST | |
|
||||
| 3 | SWDIO | |
|
||||
| 4 | SWDCLK | |
|
||||
|
|
@ -1,159 +0,0 @@
|
|||
# Board - Seriously Pro SP Racing F3 EVO
|
||||
|
||||
The Seriously Pro Racing F3 Evo board (SPRacingF3EVO) is the evolution of the first board designed specifically for Cleanflight.
|
||||
|
||||
Purchasing boards directly from SeriouslyPro / SP Racing and official retailers helps fund Cleanflight development, it's the reason the Seriously Pro boards exist! Official retailers are always listed on the SeriouslyPro.com website.
|
||||
|
||||
Full details available on the website, here:
|
||||
|
||||
http://seriouslypro.com/spracingf3evo
|
||||
|
||||
## Hardware Features
|
||||
|
||||
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
|
||||
* MicroSD-Card socket for black box flight log recorder - optimize your tuning and see the results of your setup without guesswork.
|
||||
* Race transponder built in - just turn up at a race and have your lap times recorded.
|
||||
* Features the latest Accelerometer, Gyro and Mag/Compass and Baro/Altitude sensor technology.
|
||||
* Wire up using using pin headers for all major connections for excellent crash-durability. Use either right-angled or straight pin-headers.
|
||||
* No compromise I/O. Use all the features all the time; e.g. Connect your USB + OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + 8 motors - all at the same time!
|
||||
* 8 PWM output lines for ESCs and Servos. Arranged for easy wiring on standard pin headers.
|
||||
* Supports direct connection of SBus, SumH, SumD, Spektrum1024/2048, XBus receivers. No external inverters required (built-in).
|
||||
* Supports direct connection of 3.3v Spektrum Satellite receivers via 3 pin through-hole JST-ZH connector.
|
||||
* Dedicated PPM receiver input.
|
||||
* 3 Serial Ports - NOT shared with the USB socket.
|
||||
* Telemetry port
|
||||
* Micro USB socket.
|
||||
* Dedicated output for programmable LEDs - great for orientation, racing and night flying. (Currently mutually exclusive with the Transponder).
|
||||
* Dedicated I2C port for connection of OLED display without needing flight battery.
|
||||
* Battery monitoring for voltage and current.
|
||||
* RSSI monitoring (analogue or PWM).
|
||||
* Buzzer port for audible warnings and notifications.
|
||||
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
|
||||
* Symmetrical design for a super tidy wiring.
|
||||
* JST-SH sockets only for I2C, UART2 and SWD. UART2 also on through-hole pins.
|
||||
* Flashing via USB or serial port.
|
||||
* Stackable design - perfect for integrating with OSDs and power distribution boards.
|
||||
* Standard mounting - 36x36mm with standard 30.5mm mounting holes.
|
||||
* LEDs for 3v, 5v and Status for easy diagnostics.
|
||||
* Copper-etched Cleanflight logo.
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
|
||||
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | PA10 | PA9 | YES | 2 through-hole pins. Use for connecting to OSD/GPS/BlueTooth. |
|
||||
| 2 | USART2 | PA15 | PA14 / SWCLK | YES | JST socket and PPM header. Use to connect to RX. |
|
||||
| 3 | USART3 | PB11 / AF7 | PB10 / AF7 | NO | Available on 4 through-hole pins. 3.3V signals only ! Use for GPS, Spektrum Satellite RX, SmartPort Telemetry, HoTT telemetry, etc. |
|
||||
|
||||
* You cannot use SWD and USART2 at the same time.
|
||||
* When using a Serial RX receiver the TXD (T2) pin cannot be used for telemetry. Use UART3 TXD instead.
|
||||
* One Software serial is supported in th SPRacingF3EVO_1SS version, see table below
|
||||
* Windows DFU Flashing requires Zadig (see configurator)
|
||||
|
||||
### SoftSerial
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 7 | SOFTSERIAL1 RX | SoftSerial disables Servo 5,6 |
|
||||
| 8 | SOFTSERIAL1 TX | |
|
||||
|
||||
## Pinouts
|
||||
|
||||
Full pinout details are available in the manual, here:
|
||||
|
||||
http://seriouslypro.com/files/SPRacingF3EVO-Manual-latest.pdf
|
||||
|
||||
### IO_1
|
||||
|
||||
The 6 pin IO_1 connector has the following pinouts when used in RX_SERIAL mode.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_SERIAL | Enable `feature RX_SERIAL` |
|
||||
| 4 | | |
|
||||
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
|
||||
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
|
||||
|
||||
When RX_PPM is used the IO_1 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | TELEMETRY | Enable `feature TELEMETRY` |
|
||||
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
|
||||
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
|
||||
|
||||
### IO_2
|
||||
|
||||
When TRANSPONDER is used and the IR solder pads are shorted, the 6 pin IO_2 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ------------------------- | -------------------------------------------- |
|
||||
| 1 | IR- | Short leg of the IR LED |
|
||||
| 2 | IR+ | Long leg of the IR LED |
|
||||
| 3 | CURRENT | Current Sensor |
|
||||
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
|
||||
| 5 | BUZZER+ | 5V Source |
|
||||
| 6 | BUZZER- | Buzzer signal |
|
||||
|
||||
When LEDSTRIP is used and the LED solder pads are shorted, the 6 pin IO_2 pinout is as follows.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | ------------------------- | -------------------------------------------- |
|
||||
| 1 | | |
|
||||
| 2 | LEDSTRIP | WS2812 Ledstrip data |
|
||||
| 3 | CURRENT | Current Sensor |
|
||||
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
|
||||
| 5 | BUZZER+ | 5V Source |
|
||||
| 6 | BUZZER- | Buzzer signal |
|
||||
|
||||
### UART1
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 3 | TXD | |
|
||||
| 4 | RXD | |
|
||||
|
||||
### UART2/3
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | VCC_IN | Voltage as-supplied by BEC. |
|
||||
| 3 | TXD | |
|
||||
| 4 | RXD | |
|
||||
|
||||
### Spektrum Satellite
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 3 | 3.3V | |
|
||||
| 2 | Ground | |
|
||||
| 1 | RXD | |
|
||||
|
||||
### I2C
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
|
||||
| 3 | SCL | 3.3V signals only |
|
||||
| 4 | SDA | 3.3V signals only |
|
||||
|
||||
### SWD
|
||||
|
||||
The port cannot be used at the same time as UART2.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | NRST | |
|
||||
| 3 | SWDIO | |
|
||||
| 4 | SWDCLK | |
|
||||
|
||||
|
||||
|
|
@ -1,207 +0,0 @@
|
|||
# Board - Sparky
|
||||
|
||||
The Sparky is a very low cost and very powerful board.
|
||||
|
||||
* 3 hardware serial ports.
|
||||
* Built-in serial port inverters which allows S.BUS receivers to be used without external inverters.
|
||||
* USB (can be used at the same time as the serial ports).
|
||||
* 10 PWM outputs.
|
||||
* Dedicated PPM/SerialRX input pin.
|
||||
* MPU9150 I2C Acc/Gyro/Mag
|
||||
* Baro
|
||||
|
||||
Tested with revision 1 & 2 boards.
|
||||
|
||||
## TODO
|
||||
|
||||
* Rangefinder
|
||||
* Display (via Flex port)
|
||||
* SoftSerial - though having 3 hardware serial ports makes it a little redundant.
|
||||
* Airplane PWM mappings.
|
||||
|
||||
# Voltage and current monitoring (ADC support)
|
||||
|
||||
Voltage monitoring is possible when enabled via PWM9 pin and current can be monitored via PWM8 pin. The voltage divider and current sensor need to be connected externally. The vbatscale cli parameter need to be adjusted to fit the sensor specification. For more details regarding the sensor hardware you can check here: https://github.com/TauLabs/TauLabs/wiki/User-Guide:-Battery-Configuration
|
||||
|
||||
# Flashing
|
||||
|
||||
## Via Device Firmware Upload (DFU, USB) - Windows
|
||||
|
||||
These instructions are for flashing the Sparky board under Windows using DfuSE.
|
||||
Credits go to Thomas Shue (Full video of the below steps can be found here: https://www.youtube.com/watch?v=I4yHiRVRY94)
|
||||
|
||||
Required Software:
|
||||
DfuSE Version 3.0.2 (latest version 3.0.4 causes errors): http://code.google.com/p/multipilot32/downloads/detail?name=DfuSe.rar
|
||||
STM VCP Driver 1.4.0: http://www.st.com/web/en/catalog/tools/PF257938
|
||||
|
||||
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
|
||||
|
||||
```
|
||||
Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive
|
||||
Download the latest Sparky release (inav_SPARKY.hex) from:
|
||||
https://github.com/iNavFlight/inav/releases and store it on your Hardrive
|
||||
|
||||
In your DfuSE folder go to BIN and start DfuFileMgr.exe
|
||||
Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK
|
||||
Press: "S19 or Hex.."
|
||||
Go to the folder where you saved the inav_SPARKY.hex file, select it and press open
|
||||
(you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file)
|
||||
Press: "Generate" and select the .dfu output file and location
|
||||
If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!"
|
||||
|
||||
```
|
||||
|
||||
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
|
||||
|
||||
Check the windows device manager to make sure the board is recognized correctly.
|
||||
It should show up as "STM Device in DFU mode" under Universal Serial Bus Controllers
|
||||
|
||||
If it shows up as "STMicroelectronics Virtual COM" under Ports (COM & LPT) instead then the board is not in DFU mode. Disconnect the board, short the bootloader pins again while connecting the board.
|
||||
|
||||
If the board shows up as "STM 32 Bootloader" device in the device manager, the drivers need to be updated manually.
|
||||
Select the device in the device manager, press "update drivers", select "manual update drivers" and choose the location where you extracted the STM VCP Drivers, select "let me choose which driver to install". You shoud now be able to select either the STM32 Bootloader driver or the STM in DFU mode driver. Select the later and install.
|
||||
|
||||
|
||||
Then flash the binary as below.
|
||||
|
||||
```
|
||||
In your DfuSE folder go to BIN and start DfuSeDemo.exe
|
||||
Select the Sparky Board (STM in DFU Mode) from the Available DFU and compatible HID Devices drop down list
|
||||
Press "Choose.." at the bootom of the window and select the .dfu file created in the previous step
|
||||
"File correctly loaded" should appear in the status bar
|
||||
Press "Upgrade" and confirm with "Yes"
|
||||
The status bar will show the upload progress and confirm that the upload is complete at the end
|
||||
|
||||
```
|
||||
|
||||
Disconnect and reconnect the board from USB and continue to configure it via the INAV configurator as per normal
|
||||
|
||||
|
||||
## Via Device Firmware Upload (DFU, USB) - Mac OS X / Linux
|
||||
|
||||
These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project.
|
||||
|
||||
http://www.open-tx.org/2013/07/15/dfu-util-07-for-mac-taranis-flashing-utility/
|
||||
|
||||
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
|
||||
|
||||
```
|
||||
make TARGET=SPARKY clean
|
||||
make TARGET=SPARKY binary
|
||||
```
|
||||
|
||||
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
|
||||
|
||||
Run 'dfu-util -l' to make sure the device is listed, as below.
|
||||
|
||||
```
|
||||
$ dfu-util -l
|
||||
dfu-util 0.7
|
||||
|
||||
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
|
||||
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
|
||||
This program is Free Software and has ABSOLUTELY NO WARRANTY
|
||||
Please report bugs to dfu-util@lists.gnumonks.org
|
||||
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
|
||||
```
|
||||
|
||||
Then flash the binary as below.
|
||||
|
||||
```
|
||||
dfu-util -D obj/inav_SPARKY.bin --alt 0 -R -s 0x08000000
|
||||
```
|
||||
|
||||
The output should be similar to this:
|
||||
|
||||
```
|
||||
dfu-util 0.7
|
||||
|
||||
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
|
||||
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
|
||||
This program is Free Software and has ABSOLUTELY NO WARRANTY
|
||||
Please report bugs to dfu-util@lists.gnumonks.org
|
||||
|
||||
Opening DFU capable USB device... ID 0483:df11
|
||||
Run-time device DFU version 011a
|
||||
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
|
||||
Claiming USB DFU Interface...
|
||||
Setting Alternate Setting #0 ...
|
||||
Determining device status: state = dfuERROR, status = 10
|
||||
dfuERROR, clearing status
|
||||
Determining device status: state = dfuIDLE, status = 0
|
||||
dfuIDLE, continuing
|
||||
DFU mode device DFU version 011a
|
||||
Device returned transfer size 2048
|
||||
No valid DFU suffix signature
|
||||
Warning: File has no DFU suffix
|
||||
DfuSe interface name: "Internal Flash "
|
||||
Downloading to address = 0x08000000, size = 76764
|
||||
......................................
|
||||
File downloaded successfully
|
||||
can't detach
|
||||
Resetting USB to switch back to runtime mode
|
||||
|
||||
```
|
||||
On Linux you might want to take care that the modemmanager isn't trying to use your sparky as modem getting it into bootloader mode while doing so. In doubt you probably want to uninstall it. It could also be good idea to get udev fixed. It looks like teensy did just that -> http://www.pjrc.com/teensy/49-teensy.rules (untested)
|
||||
|
||||
To make a full chip erase you can use a file created by
|
||||
```
|
||||
dd if=/dev/zero of=zero.bin bs=1 count=262144
|
||||
```
|
||||
This can be used by dfu-util.
|
||||
|
||||
## Via SWD
|
||||
|
||||
On the bottom of the board there is an SWD header socket onto switch a JST-SH connector can be soldered.
|
||||
Once you have SWD connected you can use the st-link or j-link tools to flash a binary.
|
||||
|
||||
See Sparky schematic for CONN2 pinouts.
|
||||
|
||||
## TauLabs bootloader
|
||||
|
||||
Flashing INAV will erase the TauLabs bootloader, this is not a problem and can easily be restored using the st flashloader tool.
|
||||
|
||||
# Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | Notes |
|
||||
| ----- | ------------ | --------- | ---------- | -------------------------------------------------------------- |
|
||||
| 1 | USB VCP | RX (USB) | TX (USB) | |
|
||||
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port. |
|
||||
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input |
|
||||
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
|
||||
|
||||
USB VCP *can* be used at the same time as other serial port.
|
||||
|
||||
All USART ports all support automatic hardware inversion which allows direct connection of serial rx receivers like the FrSky X4RSB - no external inverter needed.
|
||||
|
||||
|
||||
# Battery Monitoring Connections
|
||||
|
||||
| Pin | Signal | Function |
|
||||
| ---- | ------ | --------------- |
|
||||
| PWM9 | PA4 | Battery Voltage |
|
||||
| PWM8 | PA7 | Current Meter |
|
||||
|
||||
## Voltage Monitoring
|
||||
|
||||
The Sparky has no battery divider cricuit, PWM9 has an inline 10k resistor which has to be factored into the resistor calculations.
|
||||
The divider circuit should eventally create a voltage between 0v and 3.3v (MAX) at the MCU input pin.
|
||||
|
||||
WARNING: Double check the output of your voltage divider using a voltmeter *before* connecting to the FC.
|
||||
|
||||
### Example Circuit
|
||||
|
||||
For a 3Cell battery divider the following circuit works:
|
||||
|
||||
`Battery (+) ---< R1 >--- PWM9 ---< R2 >--- Battery (-)`
|
||||
|
||||
* R1 = 8k2 (Grey Red Red)
|
||||
* R2 = 2k0 (Red Black Red)
|
||||
|
||||
This gives a 2.2k for an 11.2v battery. The `vbat_scale` for this divider should be set around `52`.
|
||||
|
||||
## Current Monitoring
|
||||
|
||||
Connect a current sensor to PWM8/PA7 that gives a range between 0v and 3.3v out (MAX).
|
|
@ -358,7 +358,7 @@
|
|||
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
|
||||
| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details |
|
||||
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
||||
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
|
||||
| nav_rth_climb_first | ON | If set to ON or ON_FW_SPIRAL aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF aircraft will turn and head home immediately climbing on the way. For a fixed wing ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate, turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor) |
|
||||
| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
|
||||
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
|
||||
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue