mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-13 11:29:56 +03:00
CC3D and all its traces removed
This commit is contained in:
parent
ab404957f7
commit
dad24ac7f5
21 changed files with 8 additions and 574 deletions
|
@ -8,28 +8,12 @@ This is the option you need to select for the bootloader:
|
||||||
|
|
||||||

|

|
||||||
|
|
||||||
Currently supported on the SPRACINGF3, STM32F3DISCOVERY and CC3D.
|
Currently supported on all boards with at least 128kB of flash memory (all F3, F4 and F7).
|
||||||
|
|
||||||
## Wiring
|
|
||||||
|
|
||||||
- For the CC3D, connect [a USB to UART adapter](http://bit.ly/cf-cp2102) to the flex port.
|
|
||||||
|
|
||||||
- Ensure MSP is enabled on the flex port. Unfortunatly the main port cannot be used in the current configuration due to the inverter on this port.
|
|
||||||
|
|
||||||
- You'll only need this connection to the CC3D, do not plug in the normal USB connection.
|
|
||||||
|
|
||||||
- If you need one, I prefer the [CP2102](http://bit.ly/cf-cp2102) as it is cheap and [the driver](https://www.silabs.com/products/mcu/Pages/USBtoUARTBridgeVCPDrivers.aspx) is readily available.
|
|
||||||
|
|
||||||
- In the case that your board does not power on fully without a battery attached, it is OK to attach the battery before following the steps below. However, it may not be necessary in all cases.
|
|
||||||
|
|
||||||
## Usage
|
## Usage
|
||||||
|
|
||||||
- Plug in the USB cable and connect to your board with the INAV configurator.
|
- Plug in the USB cable and connect to your board with the INAV configurator.
|
||||||
|
|
||||||
- For boards without a built in USB/UART adapter, you'll need to plug an external one in. Here is how you wire up the CC3D. Plug your USB/UART adapter into the Flexi port:
|
|
||||||
|
|
||||||

|
|
||||||
|
|
||||||
- Open the BlHeli Suite.
|
- Open the BlHeli Suite.
|
||||||
|
|
||||||
- Ensure you have selected the correct Atmel or SILABS "Cleanflight" option under the "Select ATMEL / SILABS Interface" menu option.
|
- Ensure you have selected the correct Atmel or SILABS "Cleanflight" option under the "Select ATMEL / SILABS Interface" menu option.
|
||||||
|
|
|
@ -24,18 +24,6 @@ incorrect voltage or reversed polarity will likely fry your flight controller. E
|
||||||
has a voltage divider capable of measuring your particular battery voltage.
|
has a voltage divider capable of measuring your particular battery voltage.
|
||||||
On the first battery connection is always advisable to use a current limiter device to limit damages if something is wrong in the setup.
|
On the first battery connection is always advisable to use a current limiter device to limit damages if something is wrong in the setup.
|
||||||
|
|
||||||
### CC3D
|
|
||||||
|
|
||||||
The CC3D has no battery divider. To use voltage monitoring, you must create a divider that gives a 3.3v
|
|
||||||
MAXIMUM output when the main battery is fully charged. Connect the divider output to S5_IN/PA0/RC5.
|
|
||||||
|
|
||||||
Notes:
|
|
||||||
|
|
||||||
* S5_IN/PA0/RC5 is Pin 7 on the 8 pin connector, second to last pin, on the opposite end from the
|
|
||||||
GND/+5/PPM signal input.
|
|
||||||
|
|
||||||
* When battery monitoring is enabled on the CC3D, RC5 can no-longer be used for PWM input.
|
|
||||||
|
|
||||||
### Sparky
|
### Sparky
|
||||||
|
|
||||||
See the [Sparky board chapter](Board - Sparky.md).
|
See the [Sparky board chapter](Board - Sparky.md).
|
||||||
|
|
|
@ -1,193 +0,0 @@
|
||||||
# Board - CC3D
|
|
||||||
|
|
||||||
The OpenPilot Copter Control 3D aka CC3D is a board more tuned to Acrobatic flying or GPS based
|
|
||||||
auto-piloting. It only has one sensor, the MPU6000 SPI based Accelerometer/Gyro.
|
|
||||||
It also features a 16Mbit SPI based EEPROM chip. It has 6 ports labeled as inputs (one pin each)
|
|
||||||
and 6 ports labeled as motor/servo outputs (3 pins each).
|
|
||||||
|
|
||||||
If issues are found with this board please report via the [github issue tracker](https://github.com/iNavFlight/inav/issues).
|
|
||||||
|
|
||||||
The board has a USB port directly connected to the processor.
|
|
||||||
|
|
||||||
The board cannot currently be used for hexacopters/octocopters.
|
|
||||||
|
|
||||||
Tricopter & Airplane support is untested, please report success or failure if you try it.
|
|
||||||
|
|
||||||
# Pinouts
|
|
||||||
|
|
||||||
The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
|
|
||||||
|
|
||||||
| Pin | Function | Notes |
|
|
||||||
| --- | --------- | -------------------------------- |
|
|
||||||
| 1 | Ground | |
|
|
||||||
| 2 | +5V | |
|
|
||||||
| 3 | Unused | |
|
|
||||||
| 4 | SoftSerial1 TX / HC-SR04 trigger | |
|
|
||||||
| 5 | SoftSerial1 RX / HC-SR04 Echo / RSSI\_ADC | Used either for SOFTSERIAL, HC-SR04 Rangefinder or RSSI\_ADC*. Only one feature can be enabled at any time. |
|
|
||||||
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
|
|
||||||
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
|
|
||||||
| 8 | PPM Input | Enable `feature RX_PPM` |
|
|
||||||
|
|
||||||
*Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input.
|
|
||||||
|
|
||||||
NOTE: for the CC3D\_PPM1 build PPM input is on Pin 3 and RSSI\_ADC is on Pin 8
|
|
||||||
|
|
||||||
The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
|
|
||||||
|
|
||||||
| Pin | Function | Notes |
|
|
||||||
| --- | ----------| ------|
|
|
||||||
| 1 | MOTOR 1 | |
|
|
||||||
| 2 | MOTOR 2 | |
|
|
||||||
| 3 | MOTOR 3 | |
|
|
||||||
| 4 | MOTOR 4 | |
|
|
||||||
| 5 | LED Strip | |
|
|
||||||
| 6 | Unused | |
|
|
||||||
|
|
||||||
The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_PWM mode
|
|
||||||
|
|
||||||
| Pin | Function | Notes |
|
|
||||||
| --- | ---------| ------|
|
|
||||||
| 1 | Ground | |
|
|
||||||
| 2 | +5V | |
|
|
||||||
| 3 | Unused | |
|
|
||||||
| 4 | CH1 | |
|
|
||||||
| 5 | CH2 | |
|
|
||||||
| 6 | CH3 | |
|
|
||||||
| 7 | CH4/Battery Voltage sensor | CH4 if battery voltage sensor is disabled |
|
|
||||||
| 8 | CH5/CH4 | CH4 if battery voltage monitor is enabled|
|
|
||||||
|
|
||||||
The 6 pin RC_Output connector has the following pinouts when used in RX_PARALLEL_PWM mode
|
|
||||||
|
|
||||||
| Pin | Function | Notes |
|
|
||||||
| --- | ---------| ------|
|
|
||||||
| 1 | MOTOR 1 | |
|
|
||||||
| 2 | MOTOR 2 | |
|
|
||||||
| 3 | MOTOR 3 | |
|
|
||||||
| 4 | MOTOR 4 | |
|
|
||||||
| 5 | Unused | |
|
|
||||||
| 6 | Unused | |
|
|
||||||
|
|
||||||
# Serial Ports
|
|
||||||
|
|
||||||
| Value | Identifier | Board Markings | Notes |
|
|
||||||
| ----- | ------------ | -------------- | ------------------------------------------|
|
|
||||||
| 1 | VCP | USB PORT | |
|
|
||||||
| 2 | USART1 | MAIN PORT | Connected to an MCU controllable inverter |
|
|
||||||
| 3 | USART3 | FLEX PORT | |
|
|
||||||
| 4 | SoftSerial | RC connector | Pins 4 and 5 (Tx and Rx respectively) |
|
|
||||||
|
|
||||||
The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmission data rate is limited to 19200 baud.
|
|
||||||
|
|
||||||
To connect the GUI to the flight controller you just need a USB cable to use the Virtual Com Port (VCP) or you can use UART1 (Main Port).
|
|
||||||
|
|
||||||
CLI access is only available via the VCP by default.
|
|
||||||
|
|
||||||
# Main Port
|
|
||||||
|
|
||||||
The main port has MSP support enabled on it by default.
|
|
||||||
|
|
||||||
The main port is connected to an inverter which is automatically enabled as required. For example, if the main port is used for SBus Serial RX then an external inverter is not required.
|
|
||||||
|
|
||||||
# Flex Port
|
|
||||||
|
|
||||||
The flex port will be enabled in I2C mode unless USART3 is used. You can connect external I2C sensors and displays to this port.
|
|
||||||
|
|
||||||
You cannot use USART3 and I2C at the same time.
|
|
||||||
|
|
||||||
## Flex port pinout
|
|
||||||
|
|
||||||
| Pin | Signal | Notes |
|
|
||||||
| --- | ------------------ | ----------------------- |
|
|
||||||
| 1 | GND | |
|
|
||||||
| 2 | VCC unregulated | |
|
|
||||||
| 3 | I2C SCL / UART3 TX | 3.3v level |
|
|
||||||
| 4 | I2C SDA / UART3 RX | 3.3v level (5v tolerant |
|
|
||||||
|
|
||||||
|
|
||||||
# Flashing
|
|
||||||
|
|
||||||
There are two primary ways to get INAV onto a CC3D board.
|
|
||||||
|
|
||||||
* Single binary image mode - best mode if you don't want to use OpenPilot.
|
|
||||||
* OpenPilot Bootloader compatible image mode - best mode if you want to switch between OpenPilot and INAV.
|
|
||||||
|
|
||||||
## Single binary image mode.
|
|
||||||
|
|
||||||
The entire flash ram on the target processor is flashed with a single image.
|
|
||||||
|
|
||||||
The image can be flashed by using a USB to UART adapter connected to the main port when the CC3D is put into the STM32 bootloader mode, achieved by powering on the CC3D with the SBL/3.3v pads bridged.
|
|
||||||
|
|
||||||
## OpenPilot Bootloader compatible image mode.
|
|
||||||
|
|
||||||
The initial section of flash ram on the target process is flashed with a bootloader which can then run the code in the
|
|
||||||
remaining area of flash ram.
|
|
||||||
|
|
||||||
The OpenPilot bootloader code also allows the remaining section of flash to be reconfigured and re-flashed by the
|
|
||||||
OpenPilot Ground Station (GCS) via USB without requiring a USB to uart adapter.
|
|
||||||
|
|
||||||
The following features are not available:
|
|
||||||
* Display
|
|
||||||
* Rangefinder
|
|
||||||
|
|
||||||
# Restoring OpenPilot bootloader
|
|
||||||
|
|
||||||
If you have a JLink debugger, you can use JLinkExe to flash the open pilot bootloader.
|
|
||||||
|
|
||||||
1. Run JLinkExe `/Applications/SEGGER/JLink/JLinkExe`
|
|
||||||
2. `device STM32F103CB`
|
|
||||||
3. `r`
|
|
||||||
4. `h`
|
|
||||||
5. `loadbin opbl.bin, 0x08000000`
|
|
||||||
6. `q`
|
|
||||||
7. Re-plug CC3D.
|
|
||||||
|
|
||||||
Here's an example session:
|
|
||||||
|
|
||||||
```
|
|
||||||
$ /Applications/SEGGER/JLink/JLinkExe
|
|
||||||
SEGGER J-Link Commander V4.90c ('?' for help)
|
|
||||||
Compiled Aug 29 2014 09:52:38
|
|
||||||
DLL version V4.90c, compiled Aug 29 2014 09:52:33
|
|
||||||
Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04
|
|
||||||
Hardware: V7.00
|
|
||||||
S/N: -1
|
|
||||||
Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull
|
|
||||||
VTarget = 3.300V
|
|
||||||
Info: Could not measure total IR len. TDO is constant high.
|
|
||||||
Info: Could not measure total IR len. TDO is constant high.
|
|
||||||
No devices found on JTAG chain. Trying to find device on SWD.
|
|
||||||
Info: Found SWD-DP with ID 0x1BA01477
|
|
||||||
Info: Found Cortex-M3 r1p1, Little endian.
|
|
||||||
Info: FPUnit: 6 code (BP) slots and 2 literal slots
|
|
||||||
Info: TPIU fitted.
|
|
||||||
Cortex-M3 identified.
|
|
||||||
Target interface speed: 100 kHz
|
|
||||||
J-Link>device STM32F103CB
|
|
||||||
Info: Device "STM32F103CB" selected (128 KB flash, 20 KB RAM).
|
|
||||||
Reconnecting to target...
|
|
||||||
Info: Found SWD-DP with ID 0x1BA01477
|
|
||||||
Info: Found SWD-DP with ID 0x1BA01477
|
|
||||||
Info: Found Cortex-M3 r1p1, Little endian.
|
|
||||||
Info: FPUnit: 6 code (BP) slots and 2 literal slots
|
|
||||||
Info: TPIU fitted.
|
|
||||||
J-Link>r
|
|
||||||
Reset delay: 0 ms
|
|
||||||
Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
|
|
||||||
J-Link>h
|
|
||||||
PC = 0800010C, CycleCnt = 00000000
|
|
||||||
R0 = 0000000C, R1 = 0000003F, R2 = 00000000, R3 = 00000008
|
|
||||||
R4 = 00003000, R5 = 023ACEFC, R6 = 200000F0, R7 = 20000304
|
|
||||||
R8 = 023B92BC, R9 = 00000000, R10= ED691105, R11= F626177C
|
|
||||||
R12= 000F0000
|
|
||||||
SP(R13)= 20000934, MSP= 20000934, PSP= 20000934, R14(LR) = FFFFFFFF
|
|
||||||
XPSR = 01000000: APSR = nzcvq, EPSR = 01000000, IPSR = 000 (NoException)
|
|
||||||
CFBP = 00000000, CONTROL = 00, FAULTMASK = 00, BASEPRI = 00, PRIMASK = 00
|
|
||||||
J-Link>loadbin opbl.bin, 0x08000000
|
|
||||||
Downloading file [opbl.bin]...
|
|
||||||
WARNING: CPU is running at low speed (8004 kHz).
|
|
||||||
Info: J-Link: Flash download: Flash download into internal flash skipped. Flash contents already match
|
|
||||||
Info: J-Link: Flash download: Total time needed: 0.898s (Prepare: 0.709s, Compare: 0.128s, Erase: 0.000s, Program: 0.000s, Verify: 0.000s, Restore: 0.059s)
|
|
||||||
O.K.
|
|
||||||
J-Link>q
|
|
||||||
$
|
|
||||||
```
|
|
|
@ -48,6 +48,5 @@ These boards will work with INAV but are either end-of-life, limited on features
|
||||||
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|
||||||
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
|
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
|
||||||
| PARIS Sirius™ AIR HERO | F1 | AIRHERO3 | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL |
|
| PARIS Sirius™ AIR HERO | F1 | AIRHERO3 | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL |
|
||||||
| OpenPilot CC3D | F1 | CC3D, CC3D_PPM1 | NMEA | HMC5883 | BMP085, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | no |
|
|
||||||
| RMRC Seriously DODO | F3 | RMDO | All | All | All | All | All | SERIAL |
|
| RMRC Seriously DODO | F3 | RMDO | All | All | All | All | All | SERIAL |
|
||||||
| ANYFC | F4 | ANYFC | All | All | All | All | All | SERIAL |
|
| ANYFC | F4 | ANYFC | All | All | All | All | All | SERIAL |
|
||||||
|
|
|
@ -58,13 +58,3 @@ Examples of a known-working buzzers.
|
||||||
* [Radio Shack Model: 273-074 PC-BOARD 12VDC (3-16v) 70DB PIEZO BUZZER](http://www.radioshack.com/pc-board-12vdc-70db-piezo-buzzer/2730074.html#.VIAtpzHF_Si)
|
* [Radio Shack Model: 273-074 PC-BOARD 12VDC (3-16v) 70DB PIEZO BUZZER](http://www.radioshack.com/pc-board-12vdc-70db-piezo-buzzer/2730074.html#.VIAtpzHF_Si)
|
||||||
* [MultiComp MCKPX-G1205A-3700 TRANSDUCER, THRU-HOLE, 4V, 30MA](http://uk.farnell.com/multicomp/mckpx-g1205a-3700/transducer-thru-hole-4v-30ma/dp/2135914?CMP=i-bf9f-00001000)
|
* [MultiComp MCKPX-G1205A-3700 TRANSDUCER, THRU-HOLE, 4V, 30MA](http://uk.farnell.com/multicomp/mckpx-g1205a-3700/transducer-thru-hole-4v-30ma/dp/2135914?CMP=i-bf9f-00001000)
|
||||||
* [3-24V Piezo Electronic Tone Buzzer Alarm 95DB](http://www.banggood.com/3-24V-Piezo-Electronic-Tone-Buzzer-Alarm-95DB-Continuous-Sound-p-919348.html)
|
* [3-24V Piezo Electronic Tone Buzzer Alarm 95DB](http://www.banggood.com/3-24V-Piezo-Electronic-Tone-Buzzer-Alarm-95DB-Continuous-Sound-p-919348.html)
|
||||||
|
|
||||||
## Connections
|
|
||||||
|
|
||||||
### CC3D
|
|
||||||
|
|
||||||
Buzzer support on the CC3D requires that a buzzer circuit be created to which the input is PA15.
|
|
||||||
PA15 is unused and not connected according to the CC3D Revision A schematic.
|
|
||||||
Connecting to PA15 requires careful soldering.
|
|
||||||
|
|
||||||
See the [CC3D - buzzer circuit.pdf](Wiring/CC3D - buzzer circuit.pdf) for details.
|
|
||||||
|
|
|
@ -50,7 +50,6 @@ from another BEC. Just ensure that the GROUND is the same for all BEC outputs a
|
||||||
|
|
||||||
| Target | Pin | LED Strip | Signal |
|
| Target | Pin | LED Strip | Signal |
|
||||||
| --------------------- | ---- | --------- | -------|
|
| --------------------- | ---- | --------- | -------|
|
||||||
| CC3D | RCO5 | Data In | PB4 |
|
|
||||||
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
||||||
| Sparky | PWM5 | Data In | PA6 |
|
| Sparky | PWM5 | Data In | PA6 |
|
||||||
|
|
||||||
|
|
|
@ -13,10 +13,6 @@ It does this in two ways:
|
||||||
FlyDuino KISS ESCs are able to use the Oneshot125 protocol out of the box. There is only one soldering needed.
|
FlyDuino KISS ESCs are able to use the Oneshot125 protocol out of the box. There is only one soldering needed.
|
||||||
BLHeli rev13.0 also supports Oneshot125 and will be automatically selected by the ESC without additional work.
|
BLHeli rev13.0 also supports Oneshot125 and will be automatically selected by the ESC without additional work.
|
||||||
|
|
||||||
## Supported Boards
|
|
||||||
|
|
||||||
CC3D boards have been tested with a PPM receiver, however parallel PWM receivers might not work properly with this board.
|
|
||||||
|
|
||||||
## Enabling Oneshot
|
## Enabling Oneshot
|
||||||
|
|
||||||
To configure Oneshot, you must turn off any power to your ESCs.
|
To configure Oneshot, you must turn off any power to your ESCs.
|
||||||
|
|
|
@ -60,7 +60,7 @@ This pseudo-RSSI should work on all makes of Spektrum satellite RX; it is tested
|
||||||
|
|
||||||
16 channels via serial currently supported. See below how to set up your transmitter.
|
16 channels via serial currently supported. See below how to set up your transmitter.
|
||||||
|
|
||||||
* You probably need an inverter between the receiver output and the flight controller. However, some flight controllers have this built in (the main port on CC3D, for example), and doesn't need one.
|
* You probably need an inverter between the receiver output and the flight controller. However, some flight controllers have this built in and doesn't need one.
|
||||||
* Some OpenLRS receivers produce a non-inverted SBUS signal. It is possible to switch SBUS inversion off using CLI command `set sbus_inversion = OFF` when using an F3 based flight controller.
|
* Some OpenLRS receivers produce a non-inverted SBUS signal. It is possible to switch SBUS inversion off using CLI command `set sbus_inversion = OFF` when using an F3 based flight controller.
|
||||||
* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used.
|
* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used.
|
||||||
* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command). Note that channels above 8 are mapped "straight", with no remapping.
|
* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command). Note that channels above 8 are mapped "straight", with no remapping.
|
||||||
|
|
|
@ -26,14 +26,4 @@ Current meter cannot be used in conjunction with Parallel PWM and Sonar.
|
||||||
|
|
||||||
#### Constraints
|
#### Constraints
|
||||||
|
|
||||||
Current meter cannot be used in conjunction with Sonar.
|
Current meter cannot be used in conjunction with Sonar.
|
||||||
|
|
||||||
### CC3D
|
|
||||||
|
|
||||||
| Trigger | Echo | Inline 1k resistors |
|
|
||||||
| ------------- | ------------- | ------------------- |
|
|
||||||
| PB5 | PB0 | YES (3.3v input) |
|
|
||||||
|
|
||||||
#### Constraints
|
|
||||||
|
|
||||||
Sonar cannot be used in conjuction with SoftSerial or Parallel PWM.
|
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
Spektrum bind with hardware bind plug support.
|
Spektrum bind with hardware bind plug support.
|
||||||
|
|
||||||
The Spektrum bind code is actually enabled for the CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENWIIF1, ALIENWIIF3 targets.
|
The Spektrum bind code is actually enabled for the CJMCU, EUSTM32F103RC, SPARKY, ALIENWIIF1, ALIENWIIF3 targets.
|
||||||
|
|
||||||
## Configure the bind code
|
## Configure the bind code
|
||||||
|
|
||||||
|
@ -24,7 +24,7 @@ The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during bu
|
||||||
|
|
||||||
## Function
|
## Function
|
||||||
|
|
||||||
The bind code will actually work for CJMCU, EUSTM32F103RC, SPARKY targets (USART2) and CC3D target (USART3, flex port). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
|
The bind code will actually work for CJMCU, EUSTM32F103RC, SPARKY targets (USART2). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
|
||||||
|
|
||||||
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
|
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
|
||||||
|
|
||||||
|
@ -46,7 +46,7 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
|
||||||
|
|
||||||
### Supported Hardware
|
### Supported Hardware
|
||||||
|
|
||||||
CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
|
CJMCU, SPARKY, EUSTM32F103RC and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
|
||||||
|
|
||||||
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller
|
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller
|
||||||
|
|
||||||
|
|
|
@ -13,7 +13,7 @@ The PDF manual generation uses the Gimli for the conversion. It can be installed
|
||||||
All markdown files need to be registered in the ```build_manual.sh``` file individually by modifying the ```doc_files``` variable / array:
|
All markdown files need to be registered in the ```build_manual.sh``` file individually by modifying the ```doc_files``` variable / array:
|
||||||
```bash
|
```bash
|
||||||
doc_files=( 'Configuration.md'
|
doc_files=( 'Configuration.md'
|
||||||
'Board - CC3D.md'
|
'Board - SPRACINGF3.md'
|
||||||
'...'
|
'...'
|
||||||
'...'
|
'...'
|
||||||
)
|
)
|
||||||
|
|
|
@ -2,7 +2,6 @@
|
||||||
|
|
||||||
targets=("PUBLISHMETA=True" \
|
targets=("PUBLISHMETA=True" \
|
||||||
"RUNTESTS=True" \
|
"RUNTESTS=True" \
|
||||||
"TARGET=CC3D" \
|
|
||||||
"TARGET=CHEBUZZF3" \
|
"TARGET=CHEBUZZF3" \
|
||||||
"TARGET=CJMCU" \
|
"TARGET=CJMCU" \
|
||||||
"TARGET=COLIBRI_RACE" \
|
"TARGET=COLIBRI_RACE" \
|
||||||
|
|
|
@ -204,7 +204,7 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Divide by 8 if Oneshot125 is active and this is a CC3D board
|
// Divide to match output protocol
|
||||||
currentTime = currentTime / ppmCountDivisor;
|
currentTime = currentTime / ppmCountDivisor;
|
||||||
|
|
||||||
/* Capture computation */
|
/* Capture computation */
|
||||||
|
|
|
@ -86,13 +86,6 @@ void systemInit(void)
|
||||||
{
|
{
|
||||||
checkForBootLoaderRequest();
|
checkForBootLoaderRequest();
|
||||||
|
|
||||||
|
|
||||||
#ifdef CC3D
|
|
||||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
|
||||||
extern void *isr_vector_table_base;
|
|
||||||
|
|
||||||
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
|
|
||||||
#endif
|
|
||||||
// Configure NVIC preempt/priority groups
|
// Configure NVIC preempt/priority groups
|
||||||
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
||||||
|
|
||||||
|
|
|
@ -693,10 +693,6 @@ void timerInit(void)
|
||||||
{
|
{
|
||||||
memset(timerConfig, 0, sizeof (timerConfig));
|
memset(timerConfig, 0, sizeof (timerConfig));
|
||||||
|
|
||||||
#ifdef CC3D
|
|
||||||
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* enable the timer peripherals */
|
/* enable the timer peripherals */
|
||||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||||
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
|
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
|
||||||
|
|
|
@ -246,12 +246,6 @@ void validateAndFixConfig(void)
|
||||||
if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
||||||
featureClear(FEATURE_CURRENT_METER);
|
featureClear(FEATURE_CURRENT_METER);
|
||||||
}
|
}
|
||||||
#if defined(CC3D)
|
|
||||||
// There is a timer clash between PWM RX pins and motor output pins - this forces us to have same timer tick rate for these timers
|
|
||||||
// which is only possible when using brushless motors w/o oneshot (timer tick rate is PWM_TIMER_MHZ)
|
|
||||||
// On CC3D OneShot is incompatible with PWM RX
|
|
||||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD; // Motor PWM rate will be handled later
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
|
#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
|
||||||
|
@ -321,31 +315,6 @@ void validateAndFixConfig(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(CC3D) && defined(USE_DASHBOARD) && defined(USE_UART3)
|
|
||||||
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) {
|
|
||||||
featureClear(FEATURE_DASHBOARD);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(CC3D)
|
|
||||||
#if defined(CC3D_PPM1)
|
|
||||||
#if defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL1)
|
|
||||||
if ((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && feature(FEATURE_SOFTSERIAL)) {
|
|
||||||
rangefinderConfigMutable()->rangefinder_hardware = RANGEFINDER_NONE;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#else
|
|
||||||
#if defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
|
|
||||||
// shared pin
|
|
||||||
if (((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
|
|
||||||
rangefinderConfigMutable()->rangefinder_hardware = RANGEFINDER_NONE;
|
|
||||||
featureClear(FEATURE_SOFTSERIAL);
|
|
||||||
featureClear(FEATURE_RSSI_ADC);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif // CC3D_PPM1
|
|
||||||
#endif // CC3D
|
|
||||||
|
|
||||||
#ifndef USE_PMW_SERVO_DRIVER
|
#ifndef USE_PMW_SERVO_DRIVER
|
||||||
featureClear(FEATURE_PWM_SERVO_DRIVER);
|
featureClear(FEATURE_PWM_SERVO_DRIVER);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1 +0,0 @@
|
||||||
|
|
|
@ -1 +0,0 @@
|
||||||
|
|
|
@ -1,47 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include <platform.h>
|
|
||||||
#include "drivers/io.h"
|
|
||||||
#include "drivers/pwm_mapping.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|
||||||
#ifdef CC3D_PPM1
|
|
||||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
|
|
||||||
#else
|
|
||||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM }, // S1_IN
|
|
||||||
#endif
|
|
||||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / HC-SR04 trigger
|
|
||||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // S3_IN - SoftSerial RX / HC-SR04 echo / RSSI ADC
|
|
||||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // S4_IN - Current
|
|
||||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM }, // S5_IN - Vbattery
|
|
||||||
#ifdef CC3D_PPM1
|
|
||||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // S6_IN - PPM IN
|
|
||||||
#else
|
|
||||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // S6_IN - PPM IN
|
|
||||||
#endif
|
|
||||||
|
|
||||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
|
||||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
|
||||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
|
||||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
|
||||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S5_OUT
|
|
||||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S6_OUT
|
|
||||||
};
|
|
|
@ -1,212 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
|
|
||||||
|
|
||||||
#define LED0 PB3
|
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
|
|
||||||
|
|
||||||
#define BEEPER PA15
|
|
||||||
#define BEEPER_OPT PB2
|
|
||||||
|
|
||||||
#define USE_EXTI
|
|
||||||
#define GYRO_INT_EXTI PA3
|
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
|
||||||
|
|
||||||
#define USE_SPI
|
|
||||||
#define USE_SPI_DEVICE_1
|
|
||||||
#define USE_SPI_DEVICE_2
|
|
||||||
|
|
||||||
#define USE_I2C
|
|
||||||
#define USE_I2C_DEVICE_2 // Flex port - SCL/PB10, SDA/PB11
|
|
||||||
#define I2C_DEVICE_2_SHARES_UART3
|
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PA4
|
|
||||||
#define MPU6000_SPI_BUS BUS_SPI1
|
|
||||||
|
|
||||||
#define M25P16_CS_PIN PB12
|
|
||||||
#define M25P16_SPI_BUS BUS_SPI2
|
|
||||||
|
|
||||||
#define USE_FLASHFS
|
|
||||||
#define USE_FLASH_M25P16
|
|
||||||
|
|
||||||
#define USE_GYRO
|
|
||||||
#define USE_GYRO_MPU6000
|
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
|
||||||
|
|
||||||
#define USE_ACC
|
|
||||||
#define USE_ACC_MPU6000
|
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
|
||||||
|
|
||||||
// External I2C BARO
|
|
||||||
#define USE_BARO
|
|
||||||
#define BARO_I2C_BUS BUS_I2C2
|
|
||||||
#define USE_BARO_MS5611
|
|
||||||
#define USE_BARO_BMP280
|
|
||||||
|
|
||||||
// External I2C MAG
|
|
||||||
#define USE_MAG
|
|
||||||
#define MAG_I2C_BUS BUS_I2C2
|
|
||||||
#define USE_MAG_HMC5883
|
|
||||||
#define USE_MAG_QMC5883
|
|
||||||
|
|
||||||
#define USE_VCP
|
|
||||||
#define USE_UART1
|
|
||||||
#define USE_UART3
|
|
||||||
|
|
||||||
#define UART3_RX_PIN PB11
|
|
||||||
#define UART3_TX_PIN PB10
|
|
||||||
|
|
||||||
|
|
||||||
#if defined(CC3D_NRF24)
|
|
||||||
#define USE_RX_NRF24
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_RX_NRF24
|
|
||||||
#define USE_RX_SPI
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_SPI
|
|
||||||
//#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_SOFTSPI)
|
|
||||||
#define USE_RX_SYMA
|
|
||||||
//#define USE_RX_V202
|
|
||||||
#define USE_RX_CX10
|
|
||||||
//#define USE_RX_H8_3D
|
|
||||||
#define USE_RX_INAV
|
|
||||||
#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
|
||||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
|
||||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
|
||||||
|
|
||||||
//#define USE_SOFTSPI
|
|
||||||
//#define USE_RX_SOFTSPI
|
|
||||||
|
|
||||||
// RC pinouts
|
|
||||||
// RC1 GND
|
|
||||||
// RC2 power
|
|
||||||
// RC3 PB6/TIM4 unused
|
|
||||||
// RC4 PB5/TIM3 SCK / softserial1 TX / HC-SR04 trigger
|
|
||||||
// RC5 PB0/TIM3 MISO / softserial1 RX / HC-SR04 echo / RSSI ADC
|
|
||||||
// RC6 PB1/TIM3 MOSI / current
|
|
||||||
// RC7 PA0/TIM2 CSN / battery voltage
|
|
||||||
// RC8 PA1/TIM2 CE / RX_PPM
|
|
||||||
|
|
||||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
|
||||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
|
||||||
#define RX_NSS_PIN PA0
|
|
||||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
|
||||||
#define RX_CE_PIN PA1
|
|
||||||
#define RX_NSS_PIN PA0
|
|
||||||
#define RX_SCK_PIN PB5
|
|
||||||
#define RX_MOSI_PIN PB1
|
|
||||||
#define RX_MISO_PIN PB0
|
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 3
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
#define USE_SOFTSERIAL1
|
|
||||||
#define SERIAL_PORT_COUNT 4
|
|
||||||
|
|
||||||
#ifdef USE_UART1_RX_DMA
|
|
||||||
#undef USE_UART1_RX_DMA
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define SOFTSERIAL_1_TX_PIN PB5
|
|
||||||
#define SOFTSERIAL_1_RX_PIN PB0
|
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
|
||||||
|
|
||||||
#endif // USE_RX_NRF24
|
|
||||||
|
|
||||||
|
|
||||||
#define USE_ADC
|
|
||||||
#define ADC_CHANNEL_1_PIN PA0
|
|
||||||
#define ADC_CHANNEL_2_PIN PB1
|
|
||||||
|
|
||||||
#ifdef CC3D_PPM1
|
|
||||||
#define ADC_CHANNEL_3_PIN PA1
|
|
||||||
#else
|
|
||||||
#define ADC_CHANNEL_3_PIN PB0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
|
||||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
|
||||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
|
||||||
|
|
||||||
// LED strip is on PWM5 output pin
|
|
||||||
//#define USE_LED_STRIP
|
|
||||||
#define WS2811_PIN PB4
|
|
||||||
#define WS2811_TIMER TIM3
|
|
||||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
|
||||||
|
|
||||||
#define USE_SPEKTRUM_BIND
|
|
||||||
// USART3, PB11 (Flexport)
|
|
||||||
#define BIND_PIN PB11
|
|
||||||
|
|
||||||
//#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
// #define USE_RANGEFINDER
|
|
||||||
//#define USE_RANGEFINDER_HCSR04
|
|
||||||
//#define USE_RANGEFINDER_SRF10
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB0
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB5
|
|
||||||
|
|
||||||
//#define NAV_AUTO_MAG_DECLINATION
|
|
||||||
//#define NAV_GPS_GLITCH_DETECTION
|
|
||||||
#undef USE_BLACKBOX
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
|
||||||
|
|
||||||
#define DISABLE_UNCOMMON_MIXERS
|
|
||||||
|
|
||||||
#ifdef USE_RX_NRF24
|
|
||||||
#undef USE_RX_PWM
|
|
||||||
#undef USE_RX_PPM
|
|
||||||
#undef USE_SERIAL_RX
|
|
||||||
#undef USE_SPEKTRUM_BIND
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define TARGET_MOTOR_COUNT 4
|
|
||||||
|
|
||||||
// Number of available PWM outputs
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 11
|
|
||||||
|
|
||||||
// DEBUG
|
|
||||||
//#define USE_ASSERT // include assertion support code
|
|
||||||
//#define USE_ASSERT_FULL // Provide file information
|
|
||||||
//#define USE_ASSERT_STOP // stop on failed assertion
|
|
||||||
//#define USE_ASSERT_CHECK // include assertion check code (should in general a per-file define)
|
|
||||||
|
|
||||||
//#define HIL
|
|
||||||
//#define USE_FAKE_MAG
|
|
||||||
//#define USE_FAKE_BARO
|
|
||||||
//#define USE_FAKE_GPS
|
|
||||||
|
|
||||||
//#undef USE_TELEMETRY_FRSKY
|
|
||||||
//#define USE_TELEMETRY_MAVLINK
|
|
||||||
//#define USE_SERIALRX_SUMD
|
|
||||||
//#define USE_TELEMETRY_HOTT
|
|
||||||
|
|
||||||
// CC3D is widely used for airplanes - enable fw_autotune
|
|
||||||
#define AUTOTUNE_FIXED_WING
|
|
||||||
|
|
||||||
// IO - from schematics
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
|
||||||
#define TARGET_IO_PORTB 0xffff
|
|
||||||
#define TARGET_IO_PORTC ( BIT(14) )
|
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
|
|
@ -1,15 +0,0 @@
|
||||||
F1_TARGETS += $(TARGET)
|
|
||||||
FEATURES = ONBOARDFLASH HIGHEND VCP
|
|
||||||
|
|
||||||
TARGET_SRC = \
|
|
||||||
drivers/accgyro/accgyro_mpu.c \
|
|
||||||
drivers/accgyro/accgyro_mpu6000.c \
|
|
||||||
drivers/barometer/barometer_bmp280.c \
|
|
||||||
drivers/barometer/barometer_ms56xx.c \
|
|
||||||
drivers/compass/compass_hmc5883l.c \
|
|
||||||
drivers/compass/compass_qmc5883l.c \
|
|
||||||
drivers/flash_m25p16.c \
|
|
||||||
drivers/light_ws2811strip.c \
|
|
||||||
drivers/light_ws2811strip_stdperiph.c \
|
|
||||||
io/flashfs.c
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue