Merge remote-tracking branch 'upstream/master'

This commit is contained in:
Nicholas Sherlock 2015-01-14 15:44:35 +13:00
commit cf37c5247f
22 changed files with 630 additions and 187 deletions

5
.gitignore vendored
View File

@ -11,3 +11,8 @@
obj/ obj/
patches/ patches/
startup_stm32f10x_md_gcc.s startup_stm32f10x_md_gcc.s
# script-generated files
docs/Manual.pdf
README.pdf

View File

@ -47,6 +47,8 @@ Configure min/max cell voltages using the following CLI setting:
`vbat_max_cell_voltage` - maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V `vbat_max_cell_voltage` - maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V
`set vbat_warning_cell_voltage` - warning voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 34 = 3.4V
`vbat_min_cell_voltage` - minimum voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 33 = 3.3V `vbat_min_cell_voltage` - minimum voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 33 = 3.3V
e.g. e.g.
@ -54,6 +56,7 @@ e.g.
``` ```
set vbat_scale = 110 set vbat_scale = 110
set vbat_max_cell_voltage = 43 set vbat_max_cell_voltage = 43
set vbat_warning_cell_voltage = 34
set vbat_min_cell_voltage = 33 set vbat_min_cell_voltage = 33
``` ```
@ -75,7 +78,7 @@ Configure capacity using the `battery_capacity` setting, which takes a value in
The current meter may need to be configured so that the value read at the ADC input matches actual current draw. Just like you need a voltmeter to correctly calibrate your voltage reading you also need an ammeter to calibrate your current sensor. The current meter may need to be configured so that the value read at the ADC input matches actual current draw. Just like you need a voltmeter to correctly calibrate your voltage reading you also need an ammeter to calibrate your current sensor.
Use the following settings to adjust calibrtion. Use the following settings to adjust calibration.
`current_meter_scale` `current_meter_scale`
`current_meter_offset` `current_meter_offset`

View File

@ -9,8 +9,8 @@ This board does not have an onboard USB-Serial converter, so an external adapter
| Revision | Notes | | Revision | Notes |
| -------- | ----- | | -------- | ----- |
| 1 | no boot jumper at the edge of the board. | | 1 | No boot jumper pads by LED1. Uses blue and red LEDs |
| 2 | identified by no boot jumper pads at the edge of the board. | | 2 | Boot jumper pads presoldered with pins and a jumper by LED1. Uses green and red LEDs. |
Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards. Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards.
@ -24,9 +24,11 @@ Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlie
| PA1 | RC Channel 2 | | PA1 | RC Channel 2 |
| PA2 | RC Channel 3 / USART2 TX | | PA2 | RC Channel 3 / USART2 TX |
| PA3 | RC Channel 4 / USART2 RX | | PA3 | RC Channel 4 / USART2 RX |
| VCC | Power +3.3v | | VCC | Power (See note) |
| GND | Ground | | GND | Ground |
NOTE: The VCC RX Pin is not regulated and will supply what ever voltage is provided to the board, this will mean it'll provide 5v if a 5v serial connection is used. Be careful if you are using a voltage sensitive RX. A regulated 3.3v supply can be found on the top pin of column 1, just below the RX GND pin.
## Serial Connections ## Serial Connections
USART1 (along with power) is on the following pins. USART1 (along with power) is on the following pins.
@ -108,10 +110,32 @@ To flash the board:
* Click "Flash Firmware" * Click "Flash Firmware"
* You should see "Programming: SUCCESSFUL" in the log box * You should see "Programming: SUCCESSFUL" in the log box
* Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown * Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown
* Unplug the quad and solder across the 2 "BOOT0" pins - This prevents the board from going into bootloader mode on next * Unplug the quad and short the 2 "BOOT0" pins. Revision 1 boards require this to be soldered, revision 2 boards can connect the included jumper to the two pre-soldered pins - This prevents the board from going into bootloader mode on next
boot, if anything goes wrong, simply unsolder these pins and the bootloader will start, allowing you to reflash. You cannot boot, if anything goes wrong, simply disconnect these two pins and the bootloader will start, allowing you to reflash. You cannot
overwrite the bootloader. overwrite the bootloader.
# Charging
The CJMCU has on it a TP4056 Lithium battery charging IC that can charge a 1S battery at 1A using a provided 5v supply attached to the 5v serial pin.
To charge an attached battery:
* Set the power switch to OFF
* Set the charge switch to CHG
* Plug in a 1S battery to the battery pins
* Plug in a 5v supply to the 5v serial pins
The charger will finish when either the battery reaches 4.2v, or the battery's voltage is greater than the charger's input voltage.
The two nearby LEDs will show the status of charging:
| Status | Green LED | Red LED |
|--------------------|-----------|-----------|
| Charging | On | Off |
| Finished | Off | On |
| 5v not connected | Off | Off |
| Batt not connected | Flashing | On |
# Helpful Hints # Helpful Hints
* If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500 * If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500

View File

@ -27,7 +27,59 @@ Tested with revision 1 board.
# Flashing # Flashing
## Via Device Firmware Upload (DFU, USB) ## 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 (cleanflight_SPARKY.hex) from:
https://github.com/cleanflight/cleanflight/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 cleanflight_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 Cleanflight configurator as per normal
## Via Device Firmware Upload (DFU, USB) - Mac OS X
These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project. These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project.

View File

@ -35,4 +35,4 @@ Buzzer support on the CC3D requires that a buzzer circuit be created to which th
PA15 is unused and not connected according to the CC3D Revision A schematic. PA15 is unused and not connected according to the CC3D Revision A schematic.
Connecting to PA15 requires careful soldering. Connecting to PA15 requires careful soldering.
See the [CC3D - buzzer circuir.pdf](Wiring/CC3D - buzzer circuir.pdf) for details. See the [CC3D - buzzer circuit.pdf](Wiring/CC3D - buzzer circuit.pdf) for details.

View File

@ -30,3 +30,7 @@ HIGH - the channel value for the mapped channel input is around 2000
| Trim Acc Backwards | HIGH | CENTER | LOW | CENTER | | Trim Acc Backwards | HIGH | CENTER | LOW | CENTER |
| Save setting | LOW | LOW | LOW | HIGH | | Save setting | LOW | LOW | LOW | HIGH |
##### Download a graphic [pdf cheat-sheet](https://multiwii.googlecode.com/svn/branches/Hamburger/MultiWii-StickConfiguration-23_v0-5772156649.pdf) with TX stick commands.
The Latest version of this pdf can always be found [Here](https://code.google.com/p/multiwii/source/browse/#svn%2Fbranches%2FHamburger)

View File

@ -6,51 +6,72 @@ There are two types of failsafe:
2. flight controller based failsafe 2. flight controller based failsafe
Receiver based failsafe is where you, from your transmitter and receiver, configure channels to output desired signals if your receiver detects signal loss. Receiver based failsafe is where you, from your transmitter and receiver, configure channels to output desired signals if your receiver detects signal loss.
The idea is that you set throttle and other controls so the aircraft descends in a controlled manner. The idea is that you set throttle and other controls so the aircraft descends in a controlled manner. See your receiver's documentation for this method.
Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver. Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver.
It is possible to use both types at the same time and may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect. It is possible to use both types at the same time which may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect.
## Flight controller failsafe system ## Flight controller failsafe system
The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating in the case of TX/RX gear with long bind procedures before they send out valid data. The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating in the case of TX/RX gear with long bind procedures before they send out valid data.
After the failsafe has been forced a landing, the flight controller cannot be armed and has to be reset. After the failsafe has forced a landing, the flight controller cannot be armed and has to be reset.
The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably. The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably.
The failsafe is activated when: The failsafe is activated when:
Either: Either:
a) no valid channel data from the RX via Serial RX.
a) no valid channel data from the RX is received via Serial RX.
b) the first 4 Parallel PWM/PPM channels do not have valid signals. b) the first 4 Parallel PWM/PPM channels do not have valid signals.
And: And:
c) the failsafe guard time specified by `failsafe_delay` has elapsed. c) the failsafe guard time specified by `failsafe_delay` has elapsed.
## Configuration ## Configuration
There are a few settings for it, as below. When configuring the flight controller failsafe, use the following steps:
1. Configure your receiver to do one of the following:
a) Upon signal loss, send no signal/pulses over the channels
b) Send an invalid signal over the channels (for example, send values lower than 'failsafe_min_usec')
See your receiver's documentation for direction on how to accomplish one of these.
2. Set 'failsafe_off_delay' to an appropriate value based on how high you fly
3. Set 'failsafe_throttle' to a value that allows the aircraft to descend at approximately one meter per second.
These are the basic steps for flight controller failsafe configuration, see Failsafe Settings below for additional settings that may be changed.
##Failsafe Settings
Failsafe delays are configured in 0.1 second steps. Failsafe delays are configured in 0.1 second steps.
1 step = 0.1sec 1 step = 0.1sec
1 second = 10 steps 1 second = 10 steps
### `failsafe_delay` ### `failsafe_delay`
Guard time for failsafe activation after signal lost. Guard time for failsafe activation after signal lost. This is the amount of time the flight controller waits to see if it begins receiving a valid signal again before activating failsafe.
### `failsafe_off_delay` ### `failsafe_off_delay`
Delay after failsafe activates before motors finally turn off. If you fly high you may need more time. Delay after failsafe activates before motors finally turn off. This is the amount of time 'failsafe_throttle' is active. If you fly at higher altitudes you may need more time to descend safely.
### `failsafe_throttle` ### `failsafe_throttle`
Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec. Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec.
Use standard RX usec values. See Rx documentation. Use standard RX usec values. See RX documentation.
### `failsafe_min_usec` ### `failsafe_min_usec`
@ -64,7 +85,7 @@ The longest PWM/PPM pulse considered valid.
Only valid when using Parallel PWM or PPM receivers. Only valid when using Parallel PWM or PPM receivers.
This setting helps catch when your RX stops sending any data when the RX looses signal. This setting helps detect when your RX stops sending any data when the RX looses signal.
With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings
then this setting, at its default value, will allow failsafe to be activated. then this setting, at its default value, will allow failsafe to be activated.

View File

@ -51,12 +51,12 @@ uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to pow
from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs. from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs.
| Target | Pin | LED Strip | Signal | | Target | Pin | LED Strip | Signal |
| --------------------- | --- | --------- | -------| | --------------------- | ---- | --------- | -------|
| Naze/Olimexino | RC5 | Data In | PA6 | | Naze/Olimexino | RC5 | Data In | PA6 |
| CC3D | ??? | Data In | PB4 | | CC3D | RCO5 | Data In | PB4 |
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 | | ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
| Sparky | PWM5 | Data In | PA6 |
Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time. Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time.
Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips

58
docs/Mixer.md Normal file
View File

@ -0,0 +1,58 @@
# Mixer
Cleanflight supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft.
## Configuration
To use a built-in mixing configuration, you can use the Chrome configuration GUI. It includes images of the various mixer types to assist in making the proper connections. See the Configuration section of the documentation for more information on the GUI.
You can also use the Command Line Interface (CLI) to set the mixer type:
1. Use `mixer list` to see a list of supported mixes
2. Select a mixer. For example, to select TRI, use `mixer TRI`
3. You must use `save` to preserve your changes
## Supported Mixer Types
| Name | Description | Motors | Servos |
| ------------- | ------------------------- | -------------- | ---------------- |
| TRI | Tricopter | M1-M3 | S1 |
| QUADP | Quadcopter-Plus | M1-M4 | None |
| QUADX | Quadcopter-X | M1-M4 | None |
| BI | Bicopter (left/right) | M1-M2 | S1, S2 |
| GIMBAL | Gimbal control | N/A | S1, S2 |
| Y6 | Y6-copter | M1-M6 | None |
| HEX6 | Hexacopter-Plus | M1-M6 | None |
| FLYING_WING | Fixed wing; elevons | M1 | S1, S2 |
| Y4 | Y4-copter | M1-M4 | None |
| HEX6X | Hexacopter-X | M1-M6 | None |
| OCTOX8 | Octocopter-X (over/under) | M1-M8 | None |
| OCTOFLATP | Octocopter-FlatPlus | M1-M8 | None |
| OCTOFLATX | Octocopter-FlatX | M1-M8 | None |
| AIRPLANE | Fixed wing; Ax2, R, E | M1 | S1, S2, S3, S4 |
| HELI_120_CCPM | | | |
| HELI_90_DEG | | | |
| VTAIL4 | Quadcopter with V-Tail | M1-M4 | N/A |
| HEX6H | Hexacopter-H | M1-M6 | None |
| PPM_TO_SERVO | | | |
| DUALCOPTER | Dualcopter | M1-M2 | S1, S2 |
| SINGLECOPTER | Conventional helicopter | M1 | S1 |
| ATAIL4 | Quadcopter with A-Tail | M1-M4 | N/A |
| CUSTOM | User-defined | | |
## Servo filtering
A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example. Currently it can only be configured via the CLI:
1. Use `set servo_lowpass_freq_idx = nn` to select the cutoff frequency. Valid values range from 0 to 99.
2. Use `set servo_lowpass_enable = 1` to enable filtering.
The actual cutoff frequency is determined by the value of the `looptime` variable and the selected index.
The formula is:
`Frequency = 1000000 * (servo_lowpass_freq_idx + 1)*0.0025 / looptime )`
For example, if `servo_lowpass_freq_idx` is set to 40, and looptime is set to the default of 3500 us (0.0035 s), the cutoff frequency will be 29.3 Hz.

View File

@ -3,30 +3,30 @@
Cleanflight has various modes that can be toggled on or off. Modes can be enabled/disabled by stick positions, Cleanflight has various modes that can be toggled on or off. Modes can be enabled/disabled by stick positions,
auxillary receiver channels and other events such as failsafe detection. auxillary receiver channels and other events such as failsafe detection.
| ID | Short Name | Function | | MSP ID | Short Name | Function |
| --- | ---------- | -------------------------------------------------------------------- | | ------- | ---------- | -------------------------------------------------------------------- |
| 0 | ARM | Enables motors and flight stabilisation | | 0 | ARM | Enables motors and flight stabilisation |
| 1 | ANGLE | Legacy auto-level flight mode | | 1 | ANGLE | Legacy auto-level flight mode |
| 2 | HORIZON | Auto-level flight mode | | 2 | HORIZON | Auto-level flight mode |
| 3 | BARO | Altitude hold mode (Requires barometer sensor) | | 3 | BARO | Altitude hold mode (Requires barometer sensor) |
| 4 | MAG | Heading lock | | 5 | MAG | Heading lock |
| 5 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs | | 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs |
| 6 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode | | 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode |
| 7 | CAMSTAB | Camera Stabilisation | | 8 | CAMSTAB | Camera Stabilisation |
| 8 | CAMTRIG | | | 9 | CAMTRIG | |
| 9 | GPSHOME | Autonomous flight to HOME position | | 10 | GPSHOME | Autonomous flight to HOME position |
| 10 | GPSHOLD | Maintain the same longitude/lattitude | | 11 | GPSHOLD | Maintain the same longitude/lattitude |
| 11 | PASSTHRU | | | 12 | PASSTHRU | |
| 12 | BEEPERON | Enable beeping - useful for locating a crashed aircraft | | 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
| 13 | LEDMAX | | | 14 | LEDMAX | |
| 14 | LEDLOW | | | 15 | LEDLOW | |
| 15 | LLIGHTS | | | 16 | LLIGHTS | |
| 16 | CALIB | | | 17 | CALIB | |
| 17 | GOV | | | 18 | GOV | |
| 18 | OSD | Enable/Disable On-Screen-Display (OSD) | | 19 | OSD | Enable/Disable On-Screen-Display (OSD) |
| 19 | TELEMETRY | Enable telemetry via switch | | 20 | TELEMETRY | Enable telemetry via switch |
| 20 | AUTOTUNE | Autotune Pitch/Roll PIDs | | 21 | AUTOTUNE | Autotune Pitch/Roll PIDs |
| 21 | SONAR | Altitude hold mode (sonar sensor only) | | 22 | SONAR | Altitude hold mode (sonar sensor only) |
## Mode details ## Mode details

View File

@ -47,13 +47,24 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
### S.BUS ### S.BUS
16 channels via serial currently supported. 16 channels via serial currently supported. See the Serial chapter in the documentation for a configuration example.
* In most cases you will need an inverter between the receiver output and the flight controller hardware.
* 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).
These receivers are reported working: These receivers are reported working:
FrSky X4RSB 3/16ch Telemetry Receiver FrSky X4RSB 3/16ch Telemetry Receiver
http://www.frsky-rc.com/product/pro.php?pro_id=135 http://www.frsky-rc.com/product/pro.php?pro_id=135
FrSky X8R 8/16ch Telemetry Receiver
http://www.frsky-rc.com/product/pro.php?pro_id=105
Futaba R2008SB 2.4GHz S-FHSS
http://www.futaba-rc.com/systems/futk8100-8j/
#### OpenTX S.BUS configuration #### OpenTX S.BUS configuration
If using OpenTX set the transmitter module to D16 mode and select CH1-16 on the transmitter before binding to allow reception If using OpenTX set the transmitter module to D16 mode and select CH1-16 on the transmitter before binding to allow reception
@ -112,7 +123,7 @@ Only one receiver feature can be enabled at a time.
### Serial RX ### Serial RX
See the Configuration document some some RX configuration examples. See the Serial chapter for some some RX configuration examples.
For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as follows. For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as follows.

View File

@ -0,0 +1,89 @@
# Building in Ubuntu
Building for Ubuntu platform is remarkably easy. The only trick to understand is that the Ubuntu toolchain,
which they are downstreaming from Debian, is not compatible with Cleanflight. We suggest that you take an
alternative PPA from Terry Guo, found here:
https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded
This PPA has several compiler versions and platforms available. For many hardware platforms (notably Naze)
the 4.9.3 compiler will work fine. For some, older compiler 4.8 (notably Sparky) is more appropriate. We
suggest you build with 4.9.3 first, and try to see if you can connect to the CLI or run the Configurator.
If you cannot, please see the section below for further hints on what you might do.
## Setup GNU ARM Toolchain
Note specifically the last paragraph of Terry's PPA documentation -- Ubuntu carries its own package for
`gcc-arm-none-eabi`, so you'll have to remove it, and then pin the one from the PPA.
For your release, you should first remove any older pacakges (from Debian or Ubuntu directly), introduce
Terry's PPA, and update:
```
sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded
sudo apt-get update
```
For Ubuntu 14.10 (current release, called Utopic Unicorn), you should pin:
```
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0utopic12
```
For Ubuntu 14.04 (an LTS as of Q1'2015, called Trusty Tahr), you should pin:
```
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0trusty12
```
For Ubuntu 12.04 (previous LTS, called Precise Penguin), you should pin:
```
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0precise12
```
## Building on Ubuntu
After the ARM toolchain from Terry is installed, you should be able to build from source.
```
cd src
git clone git@github.com:cleanflight/cleanflight.git
cd cleanflight
make TARGET=NAZE
```
You'll see a set of files being compiled, and finally linked, yielding both an ELF and then a HEX:
```
...
arm-none-eabi-size ./obj/main/cleanflight_NAZE.elf
text data bss dec hex filename
97164 320 11080 108564 1a814 ./obj/main/cleanflight_NAZE.elf
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/cleanflight_NAZE.elf obj/cleanflight_NAZE.hex
$ ls -la obj/cleanflight_NAZE.hex
-rw-rw-r-- 1 pim pim 274258 Jan 12 21:45 obj/cleanflight_NAZE.hex
```
You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file.
## Bricked/Bad build?
Users have reported that the 4.9.3 compiler for ARM produces bad builds, for example on the Sparky hardware platform.
It is very likely that using an older compiler would be fine -- Terry happens to have also a 4.8 2014q2 build in his
PPA - to install this, you can fetch the `.deb` directly:
http://ppa.launchpad.net/terry.guo/gcc-arm-embedded/ubuntu/pool/main/g/gcc-arm-none-eabi/
and use `dpkg` to install:
```
sudo dpkg -i gcc-arm-none-eabi_4-8-2014q2-0saucy9_amd64.deb
```
Make sure to remove `obj/` and `make clean`, before building again.
## Updating and rebuilding
Navigate to the local cleanflight repository and use the following steps to pull the latest changes and rebuild your version of cleanflight:
```
cd src/cleanflight
git reset --hard
git pull
make clean TARGET=NAZE
make
```
Credit goes to K.C. Budd, AKfreak for testing, and pulsar for doing the long legwork that yielded this very short document.

View File

@ -214,7 +214,8 @@ static const blackboxGPSFieldDefinition_t blackboxGpsGFields[] = {
{"GPS_coord[0]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, {"GPS_coord[0]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)},
{"GPS_coord[1]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, {"GPS_coord[1]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)},
{"GPS_altitude", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, {"GPS_altitude", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)} {"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"GPS_ground_course",UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}
}; };
// GPS home frame // GPS home frame
@ -247,13 +248,25 @@ extern uint8_t motorCount;
//From mw.c: //From mw.c:
extern uint32_t currentTime; extern uint32_t currentTime;
static const int SERIAL_CHUNK_SIZE = 16; // How many bytes should we transmit per loop iteration?
static uint8_t serialChunkSize = 16;
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
static uint32_t startTime; static struct {
static unsigned int headerXmitIndex; uint32_t headerIndex;
static int fieldXmitIndex;
/* Since these fields are used during different blackbox states (never simultaneously) we can
* overlap them to save on RAM
*/
union {
int fieldIndex;
int serialBudget;
uint32_t startTime;
} u;
} xmitState;
static uint32_t blackboxConditionCache;
static uint32_t blackboxIteration; static uint32_t blackboxIteration;
static uint32_t blackboxPFrameIndex, blackboxIFrameIndex; static uint32_t blackboxPFrameIndex, blackboxIFrameIndex;
@ -570,7 +583,7 @@ static void writeTag8_8SVB(int32_t *values, int valueCount)
} }
} }
static bool testBlackboxCondition(FlightLogFieldCondition condition) static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
{ {
switch (condition) { switch (condition) {
case FLIGHT_LOG_FIELD_CONDITION_ALWAYS: case FLIGHT_LOG_FIELD_CONDITION_ALWAYS:
@ -585,19 +598,10 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
return masterConfig.mixerMode == MIXER_TRI; return masterConfig.mixerMode == MIXER_TRI;
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2:
return currentProfile->pidProfile.P8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0] != 0;
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2:
return currentProfile->pidProfile.I8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0] != 0;
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
@ -627,22 +631,39 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition)
} }
} }
static void blackboxBuildConditionCache()
{
FlightLogFieldCondition cond;
blackboxConditionCache = 0;
for (cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
if (testBlackboxConditionUncached(cond))
blackboxConditionCache |= 1 << cond;
}
}
static bool testBlackboxCondition(FlightLogFieldCondition condition)
{
return (blackboxConditionCache & (1 << condition)) != 0;
}
static void blackboxSetState(BlackboxState newState) static void blackboxSetState(BlackboxState newState)
{ {
//Perform initial setup required for the new state //Perform initial setup required for the new state
switch (newState) { switch (newState) {
case BLACKBOX_STATE_SEND_HEADER: case BLACKBOX_STATE_SEND_HEADER:
startTime = millis(); xmitState.headerIndex = 0;
headerXmitIndex = 0; xmitState.u.startTime = millis();
break; break;
case BLACKBOX_STATE_SEND_FIELDINFO: case BLACKBOX_STATE_SEND_FIELDINFO:
case BLACKBOX_STATE_SEND_GPS_G_HEADERS: case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
case BLACKBOX_STATE_SEND_GPS_H_HEADERS: case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
headerXmitIndex = 0; xmitState.headerIndex = 0;
fieldXmitIndex = -1; xmitState.u.fieldIndex = -1;
break; break;
case BLACKBOX_STATE_SEND_SYSINFO: case BLACKBOX_STATE_SEND_SYSINFO:
headerXmitIndex = 0; xmitState.headerIndex = 0;
break; break;
case BLACKBOX_STATE_RUNNING: case BLACKBOX_STATE_RUNNING:
blackboxIteration = 0; blackboxIteration = 0;
@ -855,6 +876,15 @@ static void configureBlackboxPort(void)
previousBaudRate = blackboxPort->baudRate; previousBaudRate = blackboxPort->baudRate;
} }
} }
/*
* We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If
* about looptime microseconds elapse between our writes, this is the budget of how many bytes we should
* transmit with each write.
*
* 9 / 1250 = 7200 / 1000000
*/
serialChunkSize = max((masterConfig.looptime * 9) / 1250, 4);
} }
static void releaseBlackboxPort(void) static void releaseBlackboxPort(void)
@ -887,6 +917,13 @@ void startBlackbox(void)
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
/*
* We use conditional tests to decide whether or not certain fields should be logged. Since our headers
* must always agree with the logged data, the results of these tests must not change during logging. So
* cache those now.
*/
blackboxBuildConditionCache();
blackboxSetState(BLACKBOX_STATE_SEND_HEADER); blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
} }
} }
@ -922,6 +959,7 @@ static void writeGPSFrame()
writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]); writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]);
writeUnsignedVB(GPS_altitude); writeUnsignedVB(GPS_altitude);
writeUnsignedVB(GPS_speed); writeUnsignedVB(GPS_speed);
writeUnsignedVB(GPS_ground_course);
gpsHistory.GPS_numSat = GPS_numSat; gpsHistory.GPS_numSat = GPS_numSat;
gpsHistory.GPS_coord[0] = GPS_coord[0]; gpsHistory.GPS_coord[0] = GPS_coord[0];
@ -982,7 +1020,7 @@ static void loadBlackboxState(void)
* Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
* should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition. * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
* *
* Set headerXmitIndex to 0 and fieldXmitIndex to -1 before calling for the first time. * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
* *
* secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
* fieldDefinition and secondCondition arrays. * fieldDefinition and secondCondition arrays.
@ -1002,23 +1040,23 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
* We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
* the whole header. * the whole header.
*/ */
if (fieldXmitIndex == -1) { if (xmitState.u.fieldIndex == -1) {
if (headerXmitIndex >= headerCount) if (xmitState.headerIndex >= headerCount)
return false; //Someone probably called us again after we had already completed transmission return false; //Someone probably called us again after we had already completed transmission
charsWritten = blackboxPrint("H Field "); charsWritten = blackboxPrint("H Field ");
charsWritten += blackboxPrint(headerNames[headerXmitIndex]); charsWritten += blackboxPrint(headerNames[xmitState.headerIndex]);
charsWritten += blackboxPrint(":"); charsWritten += blackboxPrint(":");
fieldXmitIndex++; xmitState.u.fieldIndex++;
needComma = false; needComma = false;
} else } else
charsWritten = 0; charsWritten = 0;
for (; fieldXmitIndex < fieldCount && charsWritten < SERIAL_CHUNK_SIZE; fieldXmitIndex++) { for (; xmitState.u.fieldIndex < fieldCount && charsWritten < serialChunkSize; xmitState.u.fieldIndex++) {
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * fieldXmitIndex); def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
if (!conditions || testBlackboxCondition(conditions[conditionsStride * fieldXmitIndex])) { if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
if (needComma) { if (needComma) {
blackboxWrite(','); blackboxWrite(',');
charsWritten++; charsWritten++;
@ -1026,16 +1064,16 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
needComma = true; needComma = true;
// The first header is a field name // The first header is a field name
if (headerXmitIndex == 0) { if (xmitState.headerIndex == 0) {
charsWritten += blackboxPrint(def->name); charsWritten += blackboxPrint(def->name);
} else { } else {
//The other headers are integers //The other headers are integers
if (def->arr[headerXmitIndex - 1] >= 10) { if (def->arr[xmitState.headerIndex - 1] >= 10) {
blackboxWrite(def->arr[headerXmitIndex - 1] / 10 + '0'); blackboxWrite(def->arr[xmitState.headerIndex - 1] / 10 + '0');
blackboxWrite(def->arr[headerXmitIndex - 1] % 10 + '0'); blackboxWrite(def->arr[xmitState.headerIndex - 1] % 10 + '0');
charsWritten += 2; charsWritten += 2;
} else { } else {
blackboxWrite(def->arr[headerXmitIndex - 1] + '0'); blackboxWrite(def->arr[xmitState.headerIndex - 1] + '0');
charsWritten++; charsWritten++;
} }
} }
@ -1043,85 +1081,115 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
} }
// Did we complete this line? // Did we complete this line?
if (fieldXmitIndex == fieldCount) { if (xmitState.u.fieldIndex == fieldCount) {
blackboxWrite('\n'); blackboxWrite('\n');
headerXmitIndex++; xmitState.headerIndex++;
fieldXmitIndex = -1; xmitState.u.fieldIndex = -1;
} }
return headerXmitIndex < headerCount; return xmitState.headerIndex < headerCount;
} }
/** /**
* Transmit a portion of the system information headers. Begin with a xmitIndex of 0. Returns the next xmitIndex to * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
* call with, or -1 if transmission is complete. * true iff transmission is complete, otherwise call again later to continue transmission.
*/ */
static int blackboxWriteSysinfo(int xmitIndex) static bool blackboxWriteSysinfo()
{ {
union floatConvert_t { union floatConvert_t {
float f; float f;
uint32_t u; uint32_t u;
} floatConvert; } floatConvert;
switch (xmitIndex) { if (xmitState.headerIndex == 0) {
xmitState.u.serialBudget = 0;
xmitState.headerIndex = 1;
}
// How many bytes can we afford to transmit this loop?
xmitState.u.serialBudget = min(xmitState.u.serialBudget + serialChunkSize, 64);
// Most headers will consume at least 20 bytes so wait until we've built up that much link budget
if (xmitState.u.serialBudget < 20) {
return false;
}
switch (xmitState.headerIndex) {
case 0: case 0:
blackboxPrintf("H Firmware type:Cleanflight\n"); //Shouldn't ever get here
break; break;
case 1: case 1:
// Pause to allow more time for previous to transmit (it exceeds our chunk size) blackboxPrintf("H Firmware type:Cleanflight\n");
xmitState.u.serialBudget -= strlen("H Firmware type:Cleanflight\n");
break; break;
case 2: case 2:
blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); blackboxPrintf("H Firmware revision:%s\n", shortGitRevision);
/* Don't need to be super exact about the budget so don't mind the fact that we're including the length of
* the placeholder "%s"
*/
xmitState.u.serialBudget -= strlen("H Firmware revision:%s\n") + strlen(shortGitRevision);
break; break;
case 3: case 3:
// Pause to allow more time for previous to transmit blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
xmitState.u.serialBudget -= strlen("H Firmware date:%s %s\n") + strlen(buildDate) + strlen(buildTime);
break; break;
case 4: case 4:
blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
xmitState.u.serialBudget -= strlen("H P interval:%d/%d\n");
break; break;
case 5: case 5:
// Pause to allow more time for previous to transmit blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
xmitState.u.serialBudget -= strlen("H rcRate:%d\n");
break; break;
case 6: case 6:
blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
xmitState.u.serialBudget -= strlen("H minthrottle:%d\n");
break; break;
case 7: case 7:
blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
xmitState.u.serialBudget -= strlen("H maxthrottle:%d\n");
break; break;
case 8: case 8:
blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
break;
case 9:
blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
break;
case 10:
floatConvert.f = gyro.scale; floatConvert.f = gyro.scale;
blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u);
xmitState.u.serialBudget -= strlen("H gyro.scale:0x%x\n") + 6;
break;
case 9:
blackboxPrintf("H acc_1G:%u\n", acc_1G);
xmitState.u.serialBudget -= strlen("H acc_1G:%u\n");
break;
case 10:
blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
xmitState.u.serialBudget -= strlen("H vbatscale:%u\n");
break; break;
case 11: case 11:
blackboxPrintf("H acc_1G:%u\n", acc_1G);
break;
case 12:
blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
break;
case 13:
blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage, blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
xmitState.u.serialBudget -= strlen("H vbatcellvoltage:%u,%u,%u\n");
break; break;
case 14: case 12:
//Pause
break;
case 15:
blackboxPrintf("H vbatref:%u\n", vbatReference); blackboxPrintf("H vbatref:%u\n", vbatReference);
break;
case 16: xmitState.u.serialBudget -= strlen("H vbatref:%u\n");
// One more pause for good luck
break; break;
default: default:
return -1; return true;
} }
return xmitIndex + 1; xmitState.headerIndex++;
return false;
} }
/** /**
@ -1182,26 +1250,26 @@ static void blackboxPlaySyncBeep()
void handleBlackbox(void) void handleBlackbox(void)
{ {
int i, result; int i;
switch (blackboxState) { switch (blackboxState) {
case BLACKBOX_STATE_SEND_HEADER: case BLACKBOX_STATE_SEND_HEADER:
//On entry of this state, headerXmitIndex is 0 and startTime is intialised //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
/* /*
* Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit
* buffer. * buffer.
*/ */
if (millis() > startTime + 100) { if (millis() > xmitState.u.startTime + 100) {
for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) for (i = 0; i < serialChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++)
blackboxWrite(blackboxHeader[headerXmitIndex]); blackboxWrite(blackboxHeader[xmitState.headerIndex]);
if (blackboxHeader[headerXmitIndex] == '\0') if (blackboxHeader[xmitState.headerIndex] == '\0')
blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO); blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO);
} }
break; break;
case BLACKBOX_STATE_SEND_FIELDINFO: case BLACKBOX_STATE_SEND_FIELDINFO:
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1, if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1,
ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
#ifdef GPS #ifdef GPS
@ -1214,28 +1282,26 @@ void handleBlackbox(void)
break; break;
#ifdef GPS #ifdef GPS
case BLACKBOX_STATE_SEND_GPS_H_HEADERS: case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1, if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1,
ARRAY_LENGTH(blackboxGpsHFields), NULL, 0)) { ARRAY_LENGTH(blackboxGpsHFields), NULL, NULL)) {
blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS); blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS);
} }
break; break;
case BLACKBOX_STATE_SEND_GPS_G_HEADERS: case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1, if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1,
ARRAY_LENGTH(blackboxGpsGFields), NULL, 0)) { ARRAY_LENGTH(blackboxGpsGFields), NULL, NULL)) {
blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO); blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
} }
break; break;
#endif #endif
case BLACKBOX_STATE_SEND_SYSINFO: case BLACKBOX_STATE_SEND_SYSINFO:
//On entry of this state, headerXmitIndex is 0 //On entry of this state, xmitState.headerIndex is 0
result = blackboxWriteSysinfo(headerXmitIndex);
if (result == -1) //Keep writing chunks of the system info headers until it returns true to signal completion
if (blackboxWriteSysinfo())
blackboxSetState(BLACKBOX_STATE_PRERUN); blackboxSetState(BLACKBOX_STATE_PRERUN);
else
headerXmitIndex = result;
break; break;
case BLACKBOX_STATE_PRERUN: case BLACKBOX_STATE_PRERUN:
blackboxSetState(BLACKBOX_STATE_RUNNING); blackboxSetState(BLACKBOX_STATE_RUNNING);

View File

@ -29,21 +29,18 @@ typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
FLIGHT_LOG_FIELD_CONDITION_TRICOPTER, FLIGHT_LOG_FIELD_CONDITION_TRICOPTER,
FLIGHT_LOG_FIELD_CONDITION_MAG = 20, FLIGHT_LOG_FIELD_CONDITION_MAG,
FLIGHT_LOG_FIELD_CONDITION_BARO, FLIGHT_LOG_FIELD_CONDITION_BARO,
FLIGHT_LOG_FIELD_CONDITION_VBAT, FLIGHT_LOG_FIELD_CONDITION_VBAT,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
FLIGHT_LOG_FIELD_CONDITION_NEVER = 255, FLIGHT_LOG_FIELD_CONDITION_NEVER,
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
FLIGHT_LOG_FIELD_CONDITION_LAST = FLIGHT_LOG_FIELD_CONDITION_NEVER
} FlightLogFieldCondition; } FlightLogFieldCondition;
typedef enum FlightLogFieldPredictor { typedef enum FlightLogFieldPredictor {

View File

@ -35,13 +35,16 @@ void ws2811LedStripHardwareInit(void)
#ifdef CC3D #ifdef CC3D
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &GPIO_InitStructure); GPIO_Init(GPIOB, &GPIO_InitStructure);
#else #else
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
/* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */ /* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
@ -52,6 +55,7 @@ void ws2811LedStripHardwareInit(void)
/* Compute the prescaler value */ /* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
/* Time base configuration */ /* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_ClockDivision = 0;
@ -59,6 +63,7 @@ void ws2811LedStripHardwareInit(void)
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure); TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
/* PWM1 Mode configuration: Channel1 */ /* PWM1 Mode configuration: Channel1 */
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_Pulse = 0;
@ -75,6 +80,7 @@ void ws2811LedStripHardwareInit(void)
/* DMA1 Channel6 Config */ /* DMA1 Channel6 Config */
DMA_DeInit(DMA1_Channel6); DMA_DeInit(DMA1_Channel6);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1; DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;

View File

@ -26,10 +26,18 @@
#include "common/color.h" #include "common/color.h"
#include "drivers/light_ws2811strip.h" #include "drivers/light_ws2811strip.h"
#define WS2811_GPIO GPIOB #ifndef WS2811_GPIO
#define WS2811_PIN Pin_8 // TIM16_CH1 #define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PERIPHERAL RCC_AHBPeriph_GPIOB #define WS2811_GPIO GPIOB
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#endif
void ws2811LedStripHardwareInit(void) void ws2811LedStripHardwareInit(void)
{ {
@ -40,47 +48,53 @@ void ws2811LedStripHardwareInit(void)
uint16_t prescalerValue; uint16_t prescalerValue;
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE); RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1); GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, WS2811_GPIO_AF);
/* GPIOA Configuration: TIM16 Channel 1 as alternate function push-pull */ /* Configuration alternate function push-pull */
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = WS2811_PIN; GPIO_InitStructure.GPIO_Pin = WS2811_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(WS2811_GPIO, &GPIO_InitStructure); GPIO_Init(WS2811_GPIO, &GPIO_InitStructure);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM16, ENABLE); RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE);
/* Compute the prescaler value */ /* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
/* Time base configuration */ /* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM16, &TIM_TimeBaseStructure); TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
/* PWM1 Mode configuration: Channel1 */ /* PWM1 Mode configuration */
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_Pulse = 0;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OC1Init(TIM16, &TIM_OCInitStructure); TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable); TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
TIM_CtrlPWMOutputs(TIM16, ENABLE); TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
/* configure DMA */ /* configure DMA */
/* DMA clock enable */ /* DMA clock enable */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
/* DMA1 Channel Config */ /* DMA1 Channel Config */
DMA_DeInit(DMA1_Channel3); DMA_DeInit(WS2811_DMA_CHANNEL);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM16->CCR1; DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE; DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
@ -92,16 +106,15 @@ void ws2811LedStripHardwareInit(void)
DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel3, &DMA_InitStructure); DMA_Init(WS2811_DMA_CHANNEL, &DMA_InitStructure);
/* TIM16 CC1 DMA Request enable */ TIM_DMACmd(WS2811_TIMER, TIM_DMA_CC1, ENABLE);
TIM_DMACmd(TIM16, TIM_DMA_CC1, ENABLE);
DMA_ITConfig(DMA1_Channel3, DMA_IT_TC, ENABLE); DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE);
NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel3_IRQn; NVIC_InitStructure.NVIC_IRQChannel = WS2811_IRQ;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
@ -111,21 +124,45 @@ void ws2811LedStripHardwareInit(void)
ws2811UpdateStrip(); ws2811UpdateStrip();
} }
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL3
void DMA1_Channel3_IRQHandler(void) void DMA1_Channel3_IRQHandler(void)
{ {
if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) { if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) {
ws2811LedDataTransferInProgress = 0; ws2811LedDataTransferInProgress = 0;
DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel 6 DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel
DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel 6 transfer complete flag DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel transfer complete flag
} }
} }
#endif
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL2
void DMA1_Channel2_IRQHandler(void)
{
if (DMA_GetFlagStatus(DMA1_FLAG_TC2)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(DMA1_Channel2, DISABLE); // disable DMA channel
DMA_ClearFlag(DMA1_FLAG_TC2); // clear DMA1 Channel transfer complete flag
}
}
#endif
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL7
void DMA1_Channel7_IRQHandler(void)
{
if (DMA_GetFlagStatus(DMA1_FLAG_TC7)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(DMA1_Channel7, DISABLE); // disable DMA channel
DMA_ClearFlag(DMA1_FLAG_TC7); // clear DMA1 Channel transfer complete flag
}
}
#endif
void ws2811LedStripDMAEnable(void) void ws2811LedStripDMAEnable(void)
{ {
DMA_SetCurrDataCounter(DMA1_Channel3, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(TIM16, 0); TIM_SetCounter(WS2811_TIMER, 0);
TIM_Cmd(TIM16, ENABLE); TIM_Cmd(WS2811_TIMER, ENABLE);
DMA_Cmd(DMA1_Channel3, ENABLE); DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
} }

View File

@ -334,8 +334,15 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#ifdef LED_STRIP_TIMER #ifdef LED_STRIP_TIMER
// skip LED Strip output // skip LED Strip output
if (init->useLEDStrip && timerHardwarePtr->tim == LED_STRIP_TIMER) if (init->useLEDStrip) {
continue; if (timerHardwarePtr->tim == LED_STRIP_TIMER)
continue;
#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE)
if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->gpioPinSource == WS2811_PIN_SOURCE)
continue;
#endif
}
#endif #endif
#ifdef STM32F10X #ifdef STM32F10X

View File

@ -326,6 +326,7 @@ void DMA1_Channel4_IRQHandler(void)
handleUsartTxDma(s); handleUsartTxDma(s);
} }
#ifdef USE_USART2_TX_DMA
// USART2 Tx DMA Handler // USART2 Tx DMA Handler
void DMA1_Channel7_IRQHandler(void) void DMA1_Channel7_IRQHandler(void)
{ {
@ -334,8 +335,10 @@ void DMA1_Channel7_IRQHandler(void)
DMA_Cmd(DMA1_Channel7, DISABLE); DMA_Cmd(DMA1_Channel7, DISABLE);
handleUsartTxDma(s); handleUsartTxDma(s);
} }
#endif
// USART3 Tx DMA Handler // USART3 Tx DMA Handler
#ifdef USE_USART2_TX_DMA
void DMA1_Channel2_IRQHandler(void) void DMA1_Channel2_IRQHandler(void)
{ {
uartPort_t *s = &uartPort3; uartPort_t *s = &uartPort3;
@ -343,6 +346,8 @@ void DMA1_Channel2_IRQHandler(void)
DMA_Cmd(DMA1_Channel2, DISABLE); DMA_Cmd(DMA1_Channel2, DISABLE);
handleUsartTxDma(s); handleUsartTxDma(s);
} }
#endif
void usartIrqHandler(uartPort_t *s) void usartIrqHandler(uartPort_t *s)
{ {

View File

@ -121,7 +121,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define MSP_PROTOCOL_VERSION 0 #define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made #define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 1 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR #define API_VERSION_MINOR 2 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2 #define API_VERSION_LENGTH 2
@ -1097,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break; break;
case MSP_LED_STRIP_CONFIG: case MSP_LED_STRIP_CONFIG:
headSerialReply(MAX_LED_STRIP_LENGTH * 4); headSerialReply(MAX_LED_STRIP_LENGTH * 6);
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET); serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET);
@ -1441,22 +1441,29 @@ static bool processInCommand(void)
break; break;
case MSP_SET_LED_STRIP_CONFIG: case MSP_SET_LED_STRIP_CONFIG:
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; uint8_t ledCount = currentPort->dataSize / 6;
uint16_t mask; if (ledCount != MAX_LED_STRIP_LENGTH) {
// currently we're storing directions and functions in a uint16 (flags) headSerialError(0);
// the msp uses 2 x uint16_t to cater for future expansion break;
mask = read16(); }
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK; for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
uint16_t mask;
// currently we're storing directions and functions in a uint16 (flags)
// the msp uses 2 x uint16_t to cater for future expansion
mask = read16();
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
mask = read16(); mask = read16();
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK; ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
mask = read8(); mask = read8();
ledConfig->xy = CALCULATE_LED_X(mask); ledConfig->xy = CALCULATE_LED_X(mask);
mask = read8(); mask = read8();
ledConfig->xy |= CALCULATE_LED_Y(mask); ledConfig->xy |= CALCULATE_LED_Y(mask);
}
} }
break; break;
#endif #endif

View File

@ -345,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
for (c = input; *c; c++) { for (c = input; *c; c++) {
s = strchr(rcChannelLetters, *c); s = strchr(rcChannelLetters, *c);
if (s) if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
rxConfig->rcmap[s - rcChannelLetters] = c - input; rxConfig->rcmap[s - rcChannelLetters] = c - input;
} }
} }

View File

@ -69,7 +69,23 @@
#define GPS #define GPS
#define LED_STRIP #define LED_STRIP
#if 1
#define LED_STRIP_TIMER TIM16 #define LED_STRIP_TIMER TIM16
#else
// alternative LED strip configuration, tested working.
#define LED_STRIP_TIMER TIM1
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#endif
#define BLACKBOX #define BLACKBOX
#define TELEMETRY #define TELEMETRY

View File

@ -92,6 +92,41 @@
#define GPS #define GPS
#define DISPLAY #define DISPLAY
#define LED_STRIP
#if 1
// LED strip configuration using PWM motor output pin 5.
#define LED_STRIP_TIMER TIM16
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource6
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#endif
#if 0
// Alternate LED strip pin
// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1
#define LED_STRIP_TIMER TIM17
#define USE_LED_STRIP_ON_DMA1_CHANNEL7
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource7
#define WS2811_TIMER TIM17
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17
#define WS2811_DMA_CHANNEL DMA1_Channel7
#define WS2811_IRQ DMA1_Channel7_IRQn
#endif
#define SPEKTRUM_BIND #define SPEKTRUM_BIND
// USART2, PA3 // USART2, PA3
#define BIND_PORT GPIOA #define BIND_PORT GPIOA