1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

CC3D and all its traces removed

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-04-24 08:40:32 +02:00
parent ab404957f7
commit dad24ac7f5
21 changed files with 8 additions and 574 deletions

View file

@ -8,28 +8,12 @@ This is the option you need to select for the bootloader:
![Flashing BlHeli Bootloader](assets/images/blheli-bootloader.png)
Currently supported on the SPRACINGF3, STM32F3DISCOVERY and CC3D.
## 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.
Currently supported on all boards with at least 128kB of flash memory (all F3, F4 and F7).
## Usage
- 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:
![Flashing BlHeli Bootloader](assets/images/serial1wire-cc3d-wiring.jpg)
- Open the BlHeli Suite.
- Ensure you have selected the correct Atmel or SILABS "Cleanflight" option under the "Select ATMEL / SILABS Interface" menu option.

View file

@ -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.
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
See the [Sparky board chapter](Board - Sparky.md).

View file

@ -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
$
```

View file

@ -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 |
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
| 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 |
| ANYFC | F4 | ANYFC | All | All | All | All | All | SERIAL |

View file

@ -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)
* [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)
## 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.

View file

@ -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 |
| --------------------- | ---- | --------- | -------|
| CC3D | RCO5 | Data In | PB4 |
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
| Sparky | PWM5 | Data In | PA6 |

View file

@ -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.
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
To configure Oneshot, you must turn off any power to your ESCs.

View file

@ -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.
* 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.
* 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.

View file

@ -26,14 +26,4 @@ Current meter cannot be used in conjunction with Parallel PWM and Sonar.
#### Constraints
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.
Current meter cannot be used in conjunction with Sonar.

View file

@ -2,7 +2,7 @@
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
@ -24,7 +24,7 @@ The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during bu
## 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.
@ -46,7 +46,7 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### 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

View file

@ -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:
```bash
doc_files=( 'Configuration.md'
'Board - CC3D.md'
'Board - SPRACINGF3.md'
'...'
'...'
)