diff --git a/.gitignore b/.gitignore
index cf98d4de42..34dd269dd7 100644
--- a/.gitignore
+++ b/.gitignore
@@ -11,3 +11,8 @@
obj/
patches/
startup_stm32f10x_md_gcc.s
+
+# script-generated files
+docs/Manual.pdf
+README.pdf
+
diff --git a/Makefile b/Makefile
index 1b4f18ba80..cda4d0421b 100644
--- a/Makefile
+++ b/Makefile
@@ -105,6 +105,12 @@ STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
+EXCLUDES = stm32f10x_crc.c \
+ stm32f10x_cec.c \
+ stm32f10x_can.c
+
+STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
+
# Search path and source files for the CMSIS sources
VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
@@ -129,6 +135,12 @@ STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
+EXCLUDES = stm32f10x_crc.c \
+ stm32f10x_cec.c \
+ stm32f10x_can.c
+
+STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
+
# Search path and source files for the CMSIS sources
VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
@@ -219,7 +231,8 @@ HIGHEND_SRC = flight/autotune.c \
telemetry/msp.c \
telemetry/smartport.c \
sensors/sonar.c \
- sensors/barometer.c
+ sensors/barometer.c \
+ blackbox/blackbox.c
NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_adxl345.c \
@@ -354,6 +367,8 @@ CJMCU_SRC = startup_stm32f10x_md_gcc.S \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
+ blackbox/blackbox.c \
+ hardware_revision.c \
$(COMMON_SRC)
CC3D_SRC = startup_stm32f10x_md_gcc.S \
diff --git a/build_docs.sh b/build_docs.sh
index 3a13d08aff..396e276d12 100755
--- a/build_docs.sh
+++ b/build_docs.sh
@@ -5,13 +5,6 @@ doc_files=(
'Installation.md'
'Configuration.md'
'Cli.md'
-
- 'Board - AlienWii32.md'
- 'Board - CC3D.md'
- 'Board - CJMCU.md'
- 'Board - Naze32.md'
- 'Board - Sparky.md'
-
'Serial.md'
'Rx.md'
'Spektrum bind.md'
@@ -29,7 +22,16 @@ doc_files=(
'Inflight Adjustments.md'
'Controls.md'
'Autotune.md'
- 'Migrating from baseflight.md')
+ 'Blackbox.md'
+ 'Migrating from baseflight.md'
+ 'Board - AlienWii32.md'
+ 'Board - CC3D.md'
+ 'Board - CJMCU.md'
+ 'Board - Naze32.md'
+ 'Board - Sparky.md'
+ 'Board - Olimexino.md'
+ 'Board - CheBuzzF3.md'
+)
if which gimli >/dev/null; then
echo "Building ${filename}.pdf"
diff --git a/docs/Autotune.md b/docs/Autotune.md
index 953d35108e..4b2af7b771 100644
--- a/docs/Autotune.md
+++ b/docs/Autotune.md
@@ -5,9 +5,10 @@ Autotune helps to automatically tune your multirotor.
## Configuration.
Autotune only works in HORIZON or ANGLE mode, before using auto-tune it's best you setup so there is as little drift as possible.
-Autotuning is best on a full battery in good flying conditions, i.e. no or minimal wind.
+Autotuning is best on a full battery in good flying conditions, i.e. no or minimal wind. Autotune does not support
+pid_controller 2 (pid_controller 0 is the Cleanflight default).
-Configure a two position switch on your transmitter to activate the AUTOTUNE and (HORIZON or ANGLE) modes using the auxilary configuration.
+Configure a two position switch on your transmitter to activate the AUTOTUNE and (HORIZON or ANGLE) modes using the auxiliary configuration.
You may find a momentary switch more suitable than a toggle switch.
diff --git a/docs/Battery.md b/docs/Battery.md
index 99cb492b8e..c233c11947 100644
--- a/docs/Battery.md
+++ b/docs/Battery.md
@@ -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
+`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
e.g.
@@ -54,6 +56,7 @@ e.g.
```
set vbat_scale = 110
set vbat_max_cell_voltage = 43
+set vbat_warning_cell_voltage = 34
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.
-Use the following settings to adjust calibrtion.
+Use the following settings to adjust calibration.
`current_meter_scale`
`current_meter_offset`
diff --git a/docs/Blackbox.md b/docs/Blackbox.md
new file mode 100644
index 0000000000..05effe956a
--- /dev/null
+++ b/docs/Blackbox.md
@@ -0,0 +1,185 @@
+# Blackbox flight data recorder
+
+
+
+## Introduction
+
+This feature transmits your flight data information on every control loop iteration over a serial port to an external
+logging device to be recorded.
+
+After your flight, you can process the resulting logs on your computer to either turn them into CSV (comma-separated
+values) or render your flight log as a video using the tools `blackbox_decode` and `blackbox_render`. Those tools can be
+found in this repository:
+
+https://github.com/cleanflight/blackbox-tools
+
+You can also view your flight logs using your web browser with the interactive log viewer:
+
+https://github.com/cleanflight/blackbox-log-viewer
+
+## Logged data
+The blackbox records flight data on every iteration of the flight control loop. It records the current time in
+microseconds, P, I and D corrections for each axis, your RC command stick positions (after applying expo curves),
+gyroscope data, accelerometer data (after your configured low-pass filtering), barometer readings, 3-axis magnetometer
+readings, raw VBAT measurements, and the command being sent to each motor speed controller. This is all stored without
+any approximation or loss of precision, so even quite subtle problems should be detectable from the fight data log.
+
+Currently, the blackbox attempts to log GPS data whenever new GPS data is available, but this has not been tested yet.
+The CSV decoder and video renderer do not yet show any of the GPS data (though this will be added). If you have a working
+GPS, please send in your logs so I can get the decoding implemented.
+
+The data rate for my quadcopter using a looptime of 2400 is about 10.25kB/s. This allows about 18 days of flight logs
+to fit on a 16GB MicroSD card, which ought to be enough for anybody :).
+
+## Supported configurations
+
+The maximum data rate for the flight log is fairly restricted, so anything that increases the load can cause the flight
+log to drop frames and contain errors.
+
+The Blackbox was developed and tested on a quadcopter. It has also been tested on a tricopter. It should work on
+hexacopters or octocopters, but as they transmit more information to the flight log (due to having more motors), the
+number of dropped frames may increase. The `blackbox_render` tool only supports tri and quadcopters (please send me
+flight logs from other craft, and I can add support for them!)
+
+Cleanflight's `looptime` setting will decide how many times per second an update is saved to the flight log. The
+software was developed on a craft with a looptime of 2400. Any looptime smaller than this will put more strain on the
+data rate. The default looptime on Cleanflight is 3500. If you're using a looptime of 2000 or smaller, you will probably
+need to reduce the sampling rate in the Blackbox settings, see the later section on configuring the Blackbox feature for
+details.
+
+## Hardware
+
+The blackbox software is designed to be used with an [OpenLog serial data logger][] and a microSDHC card. You need a
+little prep to get the OpenLog ready for use, so here are the details:
+
+### Firmware
+
+The OpenLog ships with standard OpenLog 3 firmware installed. However, in order to reduce the number of dropped frames,
+it should be reflashed with the [OpenLog Light firmware][] or the special [OpenLog Blackbox firmware][] . The Blackbox
+variant of the firmware ensures that the OpenLog is running at the correct baud-rate and does away for the need for a
+`CONFIG.TXT` file to set up the OpenLog.
+
+You can find the Blackbox version of the OpenLog firmware [here](https://github.com/cleanflight/blackbox-firmware),
+along with instructions for installing it onto your OpenLog.
+
+[OpenLog serial data logger]: https://www.sparkfun.com/products/9530
+[OpenLog Light firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light
+[OpenLog Blackbox firmware]: https://github.com/cleanflight/blackbox-firmware
+
+### microSDHC
+
+Your choice of microSDHC card is very important to the performance of the system. The OpenLog relies on being able to
+make many small writes to the card with minimal delay, which not every card is good at. A faster SD-card speed rating is
+not a guarantee of better performance.
+
+#### microSDHC cards known to have poor performance
+
+ - Generic 4GB Class 4 microSDHC card - the rate of missing frames is about 1%, and is concentrated around the most
+ interesting parts of the log!
+
+#### microSDHC cards known to have good performance
+
+ - Transcend 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
+ - Sandisk Extreme 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
+
+You should format any card you use with the [SD Association's special formatting tool][] , as it will give the OpenLog
+the best chance of writing at high speed. You must format it with either FAT, or with FAT32 (recommended).
+
+[SD Association's special formatting tool]: https://www.sdcard.org/downloads/formatter_4/
+
+### OpenLog configuration
+
+This section applies only if you are using the OpenLog or OpenLog Light original firmware on the OpenLog. If you flashed
+it with the special OpenLog Blackbox firmware, you don't need to configure it further.
+
+Power up the OpenLog with a microSD card inside, wait 10 seconds or so, then power it down and plug the microSD card
+into your computer. You should find a "CONFIG.TXT" file on the card. Edit it in a text editor to set the first number
+(baud) to 115200. Set esc# to 0, mode to 0, and echo to 0. Save the file and put the card back into your OpenLog, it
+should use those settings from now on.
+
+If your OpenLog didn't write a CONFIG.TXT file, create a CONFIG.TXT file with these contents and store it in the root
+of the MicroSD card:
+
+```
+115200,26,0,0,1,0,1
+baud,escape,esc#,mode,verb,echo,ignoreRX
+```
+
+## Enabling this feature (CLI)
+
+Enable the Blackbox feature by typing in `feature BLACKBOX` and pressing enter. You also need to assign the Blackbox to
+one of [your serial ports][] . A 115200 baud port is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx
+header in the center of the board).
+
+For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough.
+
+Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go!
+
+[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md
+[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en
+
+## Configuring this feature
+
+The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control
+the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which
+decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs
+every iteration.
+
+If you are using a short looptime like 2000 or faster, or you're using a slower MicroSD card, you will need to reduce
+this rate to reduce the number of corrupted logged frames. A rate of 1/2 is likely to work for most craft.
+
+You can change these settings by entering the CLI tab in the Cleanflight Configurator and using the `set` command, like so:
+
+```
+set blackbox_rate_num = 1
+set blackbox_rate_denom = 2
+```
+
+### Serial port
+
+Connect the "TX" pin of the serial port you've chosen to the OpenLog's "RXI" pin. Don't connect the serial port's RX
+pin to the OpenLog.
+
+### Protection
+
+The OpenLog can be wrapped in black electrical tape or heat-shrink in order to insulate it from conductive frames (like
+carbon fiber), but this makes its status LEDs impossible to see. I recommend wrapping it with some clear heatshrink
+tubing instead.
+
+
+
+## Usage
+
+The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm. Each time the OpenLog is
+power-cycled, it begins a fresh new log file. If you arm and disarm several times without cycling the power (recording
+several flights), those logs will be combined together into one file. The command line tools will ask you to pick which
+one of these flights you want to display/decode.
+
+If your craft has a buzzer attached, a short beep will be played when you arm. You can later use this beep to
+synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line in the flight
+data log, which you can sync against the beep in your recorded audio track).
+
+The OpenLog requires a couple of seconds of delay after connecting the battery before it's ready to record, so don't
+arm your craft immediately after connecting the battery (you'll probably be waiting for the flight controller to become
+ready during that time anyway!)
+
+You should also wait a few seconds after disarming the quad to allow the OpenLog to finish saving its data.
+
+Don't insert or remove the SD card while the OpenLog is powered up.
+
+## Converting logs to CSV or PNG
+After your flights, you'll have a series of files labeled "LOG00001.TXT" etc. on the microSD card. You'll need to
+decode these with the `blackbox_decode` tool to create a CSV (comma-separated values) file for analysis, or render them
+into a series of PNG frames with `blackbox_render` tool, which you could then convert into a video using another
+software package.
+
+You'll find those tools along with instructions for using them in this repository:
+
+https://github.com/cleanflight/blackbox-tools
+
+You can also view your .TXT flight log files interactively using your web browser with the Cleanflight Blackbox Explorer
+tool:
+
+https://github.com/cleanflight/blackbox-log-viewer
+
+This allows you to scroll around a graphed version of your log and examine your log in detail.
\ No newline at end of file
diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md
index d321e90493..a377206101 100644
--- a/docs/Board - CJMCU.md
+++ b/docs/Board - CJMCU.md
@@ -9,8 +9,8 @@ This board does not have an onboard USB-Serial converter, so an external adapter
| Revision | Notes |
| -------- | ----- |
-| 1 | no boot jumper at the edge of the board. |
-| 2 | identified by no boot jumper pads at the edge of the board. |
+| 1 | No boot jumper pads by LED1. Uses blue and red LEDs |
+| 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.
@@ -24,9 +24,11 @@ Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlie
| PA1 | RC Channel 2 |
| PA2 | RC Channel 3 / USART2 TX |
| PA3 | RC Channel 4 / USART2 RX |
-| VCC | Power +3.3v |
+| VCC | Power (See note) |
| 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
USART1 (along with power) is on the following pins.
@@ -108,10 +110,32 @@ To flash the board:
* Click "Flash Firmware"
* 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
- * Unplug the quad and solder across the 2 "BOOT0" 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
+ * 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 disconnect these two pins and the bootloader will start, allowing you to reflash. You cannot
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
* If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500
diff --git a/targets/ChebuzzF3/notes.txt b/docs/Board - ChebuzzF3.md
similarity index 90%
rename from targets/ChebuzzF3/notes.txt
rename to docs/Board - ChebuzzF3.md
index 25e2448fac..c729207814 100644
--- a/targets/ChebuzzF3/notes.txt
+++ b/docs/Board - ChebuzzF3.md
@@ -1,13 +1,12 @@
-ChebuzzF3
+# Board - ChebuzzF3
-Author: Dominic Clifton
+The ChebuzzF3 is a daugter board which connects to the bottom of an STM32F3Discovery board and provides pin headers and ports for various FC connections.
All connections were traced using a multimeter and then verified against the TauLabs source code using the revision linked.
https://github.com/TauLabs/TauLabs/blob/816760dec2a20db7fb9ec1a505add240e696c31f/flight/targets/flyingf3/board-info/board_hw_defs.c
-
-Connections
+## Connections
Board orientation.
@@ -15,7 +14,7 @@ These notes assume that when the board is placed with the header pins facing up,
Inner means between the two rows of header sockets, outer means between the left/right board edges and the header sockets.
-SPI2 / External SPI
+### SPI2 / External SPI
sclk GPIOB 13
miso GPIOB 14
@@ -25,7 +24,7 @@ mosi GPIOB 15
There are 4 pins, labelled CS1-4 next to a label that reads Ext SPI. The 3rd pin is connected to the flash chip on
the bottom right inner of the board. The other pins on the flash chip are wired up to PB3/4/5
-SPI3 / SPI
+### SPI3 / SPI
sclk GPIOB 3
miso GPIOB 4
@@ -36,7 +35,33 @@ ssel 2 GPIOB 11 / Ext SPI CS2
ssel 3 GPIOB 12 / Ext SPI CS3 - wired up to Slave Select of M25P16 15MBitFlash chip
ssel 4 GPIOB 13 / Ext SPI CS4 - not usable since it is used for SPI2 sclk
+### RC Input
+INPUT
+PA8 / CH1 - TIM1_CH1
+PB8 / CH2 - TIM16_CH1
+PB9 / CH3 - TIM17_CH1
+PC6 / CH4 - TIM8_CH1
+PC7 / CH5 - TIM8_CH2
+PC8 / CH6 - TIM8_CH3
+PF9 / CH7 - TIM15_CH1
+PF10 / CH8 - TIM15_CH2
+
+### PWM Outputs
+
+OUTPUT
+PD12 / CH1 - TIM4_CH1
+PD13 / CH2 - TIM4_CH2
+PD14 / CH3 - TIM4_CH3
+PD15 / CH4 - TIM4_CH4
+PA1 / CH5 - TIM2_CH2
+PA2 / CH6 - TIM2_CH3
+PA3 / CH7 - TIM2_CH4
+PB0 / CH8 - TIM3_CH3
+PB1 / CH9 - TIM3_CH4
+PA4 / CH10 - TIM3_CH2
+
+### Other ports
There is space for a MS5611 pressure sensor at the top left inner of the board.
@@ -68,25 +93,3 @@ There are sockets for 5 UARTs labelled USART1-5.
There is a socket labelled RX_IN.
GPIOD 2 / PD2 / RX_IN
-
-INPUT
-PA8 / CH1 - TIM1_CH1
-PB8 / CH2 - TIM16_CH1
-PB9 / CH3 - TIM17_CH1
-PC6 / CH4 - TIM8_CH1
-PC7 / CH5 - TIM8_CH2
-PC8 / CH6 - TIM8_CH3
-PF9 / CH7 - TIM15_CH1
-PF10 / CH8 - TIM15_CH2
-
-OUTPUT
-PD12 / CH1 - TIM4_CH1
-PD13 / CH2 - TIM4_CH2
-PD14 / CH3 - TIM4_CH3
-PD15 / CH4 - TIM4_CH4
-PA1 / CH5 - TIM2_CH2
-PA2 / CH6 - TIM2_CH3
-PA3 / CH7 - TIM2_CH4
-PB0 / CH8 - TIM3_CH3
-PB1 / CH9 - TIM3_CH4
-PA4 / CH10 - TIM3_CH2
diff --git a/targets/Olimexino/notes.txt b/docs/Board - Olimexino.md
similarity index 88%
rename from targets/Olimexino/notes.txt
rename to docs/Board - Olimexino.md
index b380ecb368..385f7697bb 100644
--- a/targets/Olimexino/notes.txt
+++ b/docs/Board - Olimexino.md
@@ -1,6 +1,12 @@
-Olimexino
+# Board - Olimexino
-Author: Dominic Clifton
+The Olimexino is a cheap and widely available development board
+
+This board is not recommended for cleanflight development because many of the pins needed are not broken out to header pins. A better choice for development is the Port103R, EUSTM32F103RB (F1) or the STM32F3Discovery (F3).
+
+## Connections
+
+### RC Input
INPUT
@@ -13,6 +19,8 @@ PA7 CH6 - D11 - PWM6 / SOFTSERIAL1 TX
PB0 CH7 - D27 - PWM7 / SOFTSERIAL2 RX
PB1 CH8 - D28 - PWM8 / SOFTSERIAL2 TX
+### PWM Output
+
OUTPUT
PA8 CH1 - PWM9 - D6
PA11 CH2 - PWM10 - USBDM
@@ -21,8 +29,7 @@ PB7 CH4 - PWM12 - D9
PB8 CH5 - PWM13 - D14
PB9 CH6 - PWM14 - D24
-
-Olimexino Shield V1 connections
+## Olimexino Shield V1
Headers for a CP2102 for UART1
diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md
index c0616c598f..9501b5912e 100644
--- a/docs/Board - Sparky.md
+++ b/docs/Board - Sparky.md
@@ -27,7 +27,59 @@ Tested with revision 1 board.
# 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.
diff --git a/docs/Controls.md b/docs/Controls.md
index 0171c85596..57e5578221 100644
--- a/docs/Controls.md
+++ b/docs/Controls.md
@@ -30,3 +30,7 @@ HIGH - the channel value for the mapped channel input is around 2000
| Trim Acc Backwards | HIGH | CENTER | LOW | CENTER |
| 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)
diff --git a/docs/Failsafe.md b/docs/Failsafe.md
index afeedf96be..358bbcbb38 100644
--- a/docs/Failsafe.md
+++ b/docs/Failsafe.md
@@ -6,51 +6,72 @@ There are two types of 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.
-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.
-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
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 is activated when:
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.
And:
+
c) the failsafe guard time specified by `failsafe_delay` has elapsed.
## 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.
1 step = 0.1sec
+
1 second = 10 steps
### `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`
-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`
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`
@@ -64,7 +85,7 @@ The longest PWM/PPM pulse considered valid.
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
then this setting, at its default value, will allow failsafe to be activated.
diff --git a/docs/LedStrip.md b/docs/LedStrip.md
index c0ea55ee43..86c2076dc1 100644
--- a/docs/LedStrip.md
+++ b/docs/LedStrip.md
@@ -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.
-| Target | Pin | LED Strip | Signal |
-| --------------------- | --- | --------- | -------|
-| Naze/Olimexino | RC5 | Data In | PA6 |
-| CC3D | ??? | Data In | PB4 |
-| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
-
+| Target | Pin | LED Strip | Signal |
+| --------------------- | ---- | --------- | -------|
+| Naze/Olimexino | RC5 | Data In | PA6 |
+| CC3D | RCO5 | Data In | PB4 |
+| 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.
Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips
diff --git a/docs/Mixer.md b/docs/Mixer.md
new file mode 100644
index 0000000000..777cae38d1
--- /dev/null
+++ b/docs/Mixer.md
@@ -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.
+
+
diff --git a/docs/Modes.md b/docs/Modes.md
index 047649c963..145997bfb4 100644
--- a/docs/Modes.md
+++ b/docs/Modes.md
@@ -3,30 +3,30 @@
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.
-| ID | Short Name | Function |
-| --- | ---------- | -------------------------------------------------------------------- |
-| 0 | ARM | Enables motors and flight stabilisation |
-| 1 | ANGLE | Legacy auto-level flight mode |
-| 2 | HORIZON | Auto-level flight mode |
-| 3 | BARO | Altitude hold mode (Requires barometer sensor) |
-| 4 | MAG | Heading lock |
-| 5 | 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 | CAMSTAB | Camera Stabilisation |
-| 8 | CAMTRIG | |
-| 9 | GPSHOME | Autonomous flight to HOME position |
-| 10 | GPSHOLD | Maintain the same longitude/lattitude |
-| 11 | PASSTHRU | |
-| 12 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
-| 13 | LEDMAX | |
-| 14 | LEDLOW | |
-| 15 | LLIGHTS | |
-| 16 | CALIB | |
-| 17 | GOV | |
-| 18 | OSD | Enable/Disable On-Screen-Display (OSD) |
-| 19 | TELEMETRY | Enable telemetry via switch |
-| 20 | AUTOTUNE | Autotune Pitch/Roll PIDs |
-| 21 | SONAR | Altitude hold mode (sonar sensor only) |
+| MSP ID | Short Name | Function |
+| ------- | ---------- | -------------------------------------------------------------------- |
+| 0 | ARM | Enables motors and flight stabilisation |
+| 1 | ANGLE | Legacy auto-level flight mode |
+| 2 | HORIZON | Auto-level flight mode |
+| 3 | BARO | Altitude hold mode (Requires barometer sensor) |
+| 5 | MAG | Heading lock |
+| 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs |
+| 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode |
+| 8 | CAMSTAB | Camera Stabilisation |
+| 9 | CAMTRIG | |
+| 10 | GPSHOME | Autonomous flight to HOME position |
+| 11 | GPSHOLD | Maintain the same longitude/lattitude |
+| 12 | PASSTHRU | |
+| 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
+| 14 | LEDMAX | |
+| 15 | LEDLOW | |
+| 16 | LLIGHTS | |
+| 17 | CALIB | |
+| 18 | GOV | |
+| 19 | OSD | Enable/Disable On-Screen-Display (OSD) |
+| 20 | TELEMETRY | Enable telemetry via switch |
+| 21 | AUTOTUNE | Autotune Pitch/Roll PIDs |
+| 22 | SONAR | Altitude hold mode (sonar sensor only) |
## Mode details
diff --git a/docs/Rx.md b/docs/Rx.md
index d16d66b14a..1d99c394fb 100644
--- a/docs/Rx.md
+++ b/docs/Rx.md
@@ -1,44 +1,67 @@
# Receivers (RX)
-## Parallel PWM
+A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand.
+
+There are 3 basic types of receivers:
+
+Parallel PWM Receivers
+PPM Receivers
+Serial Receivers
+
+## Parallel PWM Receivers
8 channel support, 1 channel per input pin. On some platforms using parallel input will disable the use of serial ports
and SoftSerial making it hard to use telemetry or GPS features.
-## PPM (PPM SUM or CPPM)
+## PPM Receivers
+
+PPM is sometimes known as PPM SUM or CPPM.
12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications, but readily available.
-## MultiWii serial protocol (MSP)
+These receivers are reported working:
-Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
+FrSky D4R-II
+http://www.frsky-rc.com/product/pro.php?pro_id=24
-## Spektrum
+Graupner GR24
+http://www.graupner.de/en/products/33512/product.aspx
+
+R615X Spektrum/JR DSM2/DSMX Compatible 6Ch 2.4GHz Receiver w/CPPM
+http://orangerx.com/2014/05/20/r615x-spektrumjr-dsm2dsmx-compatible-6ch-2-4ghz-receiver-wcppm-2/
+
+FrSky D8R-XP 8ch telemetry receiver, or CPPM and RSSI enabled receiver
+http://www.frsky-rc.com/product/pro.php?pro_id=21
+
+## Serial Receivers
+
+### Spektrum
8 channels via serial currently supported.
-## S.BUS
+These receivers are reported working:
-16 channels via serial currently supported.
+Lemon Rx DSMX Compatible PPM 8-Channel Receiver + Lemon DSMX Compatible Satellite with Failsafe
+http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
-## XBUS
-The firmware currently supports the MODE B version of the XBus protocol.
-Make sure to set your TX to use "MODE B" for XBUS in the TX menus!
-See here for info on JR's XBUS protocol: http://www.jrpropo.com/english/propo/XBus/
+### S.BUS
-Tested hardware: JR XG14 + RG731BX with NAZE32 (rev4)
-With the current CLI configuration:
-```
-set serialrx_provider=5
-set serial_port_2_scenario=3
-feature RX_SERIAL
-```
-
-This will set the controller to use serial RX, with XBUS_MODE_B as provider and finally the scenario to be used for serial port 2.
-Please note that your config may vary depending on the Board used.
+16 channels via serial currently supported. See the Serial chapter in the documentation for a configuration example.
-### OpenTX configuration
+* 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:
+
+FrSky X4RSB 3/16ch Telemetry Receiver
+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
+
+#### 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
of 16 channels.
@@ -47,18 +70,56 @@ OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug -
The bug prevents use of all 16 channels. Upgrade to the latest OpenTX version to allow correct reception of all 16 channels,
without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
-## SUMD
+
+### XBUS
+
+The firmware currently supports the MODE B version of the XBus protocol.
+Make sure to set your TX to use "MODE B" for XBUS in the TX menus!
+See here for info on JR's XBUS protocol: http://www.jrpropo.com/english/propo/XBus/
+
+These receivers are reported working:
+
+XG14 14ch DMSS System w/RG731BX XBus Receiver
+http://www.jramericas.com/233794/JRP00631/
+
+### SUMD
16 channels via serial currently supported.
-## SUMH
+These receivers are reported working:
+
+GR-24 receiver HoTT
+http://www.graupner.de/en/products/33512/product.aspx
+
+Graupner receiver GR-12SH+ HoTT
+http://www.graupner.de/en/products/870ade17-ace8-427f-943b-657040579906/33565/product.aspx
+
+### SUMH
8 channels via serial currently supported.
-
-### Configuration
+SUMH is a legacy Graupner protocol. Graupner have issued a firmware updates for many recivers that lets them use SUMD instead.
-See the Configuration document some some RX configuration examples.
+## MultiWii serial protocol (MSP)
+
+Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
+
+## Configuration
+
+There are 3 features that control receiver mode:
+
+```
+RX_PPM
+RX_SERIAL
+RX_PARALLEL_PWM
+RX_MSP
+```
+
+Only one receiver feature can be enabled at a time.
+
+### Serial RX
+
+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.
@@ -72,7 +133,7 @@ For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as
| XBUS_MODE_B | 5 |
-#### PPM/PWM input filtering.
+### PPM/PWM input filtering.
Hardware input filtering can be enabled if you are experiencing interference on the signal sent via your PWM/PPM RX.
diff --git a/docs/Screenshots/blackbox-screenshot-1.jpg b/docs/Screenshots/blackbox-screenshot-1.jpg
new file mode 100644
index 0000000000..72dda4904a
Binary files /dev/null and b/docs/Screenshots/blackbox-screenshot-1.jpg differ
diff --git a/docs/Serial.md b/docs/Serial.md
index 7031fe3c38..025821d0dc 100644
--- a/docs/Serial.md
+++ b/docs/Serial.md
@@ -46,6 +46,8 @@ To make configuration easier, common usage scenarios are listed below.
7 GPS-PASSTHROUGH ONLY
8 MSP ONLY
9 SMARTPORT TELEMETRY ONLY
+10 BLACKBOX ONLY
+11 MSP, CLI, BLACKBOX, GPS-PASSTHROUGH
```
### Constraints
diff --git a/docs/Wiring/blackbox-installation-1.jpg b/docs/Wiring/blackbox-installation-1.jpg
new file mode 100644
index 0000000000..c02f1fc605
Binary files /dev/null and b/docs/Wiring/blackbox-installation-1.jpg differ
diff --git a/lib/main/CMSIS/CM1/DeviceSupport/ST/STM32F30x/stm32f30x_conf.h b/lib/main/CMSIS/CM1/DeviceSupport/ST/STM32F30x/stm32f30x_conf.h
index a390e78f43..9b31e0afb7 100644
--- a/lib/main/CMSIS/CM1/DeviceSupport/ST/STM32F30x/stm32f30x_conf.h
+++ b/lib/main/CMSIS/CM1/DeviceSupport/ST/STM32F30x/stm32f30x_conf.h
@@ -32,8 +32,8 @@
/* Includes ------------------------------------------------------------------*/
/* Comment the line below to disable peripheral header file inclusion */
#include "stm32f30x_adc.h"
-#include "stm32f30x_can.h"
-#include "stm32f30x_crc.h"
+//#include "stm32f30x_can.h"
+//#include "stm32f30x_crc.h"
#include "stm32f30x_comp.h"
#include "stm32f30x_dac.h"
#include "stm32f30x_dbgmcu.h"
diff --git a/lib/main/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h b/lib/main/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h
index 1865daf1e6..0c8603d8a5 100755
--- a/lib/main/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h
+++ b/lib/main/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h
@@ -27,9 +27,9 @@
/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */
#include "stm32f10x_adc.h"
#include "stm32f10x_bkp.h"
-#include "stm32f10x_can.h"
-#include "stm32f10x_cec.h"
-#include "stm32f10x_crc.h"
+//#include "stm32f10x_can.h"
+//#include "stm32f10x_cec.h"
+//#include "stm32f10x_crc.h"
#include "stm32f10x_dac.h"
#include "stm32f10x_dbgmcu.h"
#include "stm32f10x_dma.h"
diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c
new file mode 100644
index 0000000000..574b33d4dc
--- /dev/null
+++ b/src/main/blackbox/blackbox.c
@@ -0,0 +1,1320 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+#include "version.h"
+
+#include "common/maths.h"
+#include "common/axis.h"
+#include "common/color.h"
+
+#include "drivers/gpio.h"
+#include "drivers/sensor.h"
+#include "drivers/system.h"
+#include "drivers/serial.h"
+#include "drivers/compass.h"
+#include "drivers/timer.h"
+#include "drivers/pwm_rx.h"
+#include "drivers/accgyro.h"
+#include "drivers/light_led.h"
+#include "drivers/sound_beeper.h"
+
+#include "common/printf.h"
+
+#include "flight/flight.h"
+#include "sensors/sensors.h"
+#include "sensors/boardalignment.h"
+#include "sensors/sonar.h"
+#include "sensors/compass.h"
+#include "sensors/acceleration.h"
+#include "sensors/barometer.h"
+#include "sensors/gyro.h"
+#include "sensors/battery.h"
+#include "io/beeper.h"
+#include "io/display.h"
+#include "io/escservo.h"
+#include "rx/rx.h"
+#include "io/rc_controls.h"
+#include "flight/mixer.h"
+#include "flight/altitudehold.h"
+#include "flight/failsafe.h"
+#include "flight/imu.h"
+#include "flight/autotune.h"
+#include "flight/navigation.h"
+#include "io/gimbal.h"
+#include "io/gps.h"
+#include "io/ledstrip.h"
+#include "io/serial.h"
+#include "io/serial_cli.h"
+#include "io/serial_msp.h"
+#include "io/statusindicator.h"
+#include "rx/msp.h"
+#include "telemetry/telemetry.h"
+
+#include "config/runtime_config.h"
+#include "config/config.h"
+#include "config/config_profile.h"
+#include "config/config_master.h"
+
+#include "blackbox_fielddefs.h"
+#include "blackbox.h"
+
+#define BLACKBOX_BAUDRATE 115200
+#define BLACKBOX_INITIAL_PORT_MODE MODE_TX
+#define BLACKBOX_I_INTERVAL 32
+
+#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
+
+// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
+#define STR_HELPER(x) #x
+#define STR(x) STR_HELPER(x)
+
+#define CONCAT_HELPER(x,y) x ## y
+#define CONCAT(x,y) CONCAT_HELPER(x, y)
+
+#define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
+#define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)
+#define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x)
+#define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED
+#define SIGNED FLIGHT_LOG_FIELD_SIGNED
+
+static const char blackboxHeader[] =
+ "H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
+ "H Blackbox version:1\n"
+ "H Data version:2\n"
+ "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n";
+
+static const char* const blackboxMainHeaderNames[] = {
+ "I name",
+ "I signed",
+ "I predictor",
+ "I encoding",
+ "P predictor",
+ "P encoding"
+};
+
+#ifdef GPS
+static const char* const blackboxGPSGHeaderNames[] = {
+ "G name",
+ "G signed",
+ "G predictor",
+ "G encoding"
+};
+
+static const char* const blackboxGPSHHeaderNames[] = {
+ "H name",
+ "H signed",
+ "H predictor",
+ "H encoding"
+};
+#endif
+
+/* All field definition structs should look like this (but with longer arrs): */
+typedef struct blackboxFieldDefinition_t {
+ const char *name;
+ uint8_t arr[1];
+} blackboxFieldDefinition_t;
+
+typedef struct blackboxMainFieldDefinition_t {
+ const char *name;
+ uint8_t isSigned;
+ uint8_t Ipredict;
+ uint8_t Iencode;
+ uint8_t Ppredict;
+ uint8_t Pencode;
+ uint8_t condition; // Decide whether this field should appear in the log
+} blackboxMainFieldDefinition_t;
+
+typedef struct blackboxGPSFieldDefinition_t {
+ const char *name;
+ uint8_t isSigned;
+ uint8_t predict;
+ uint8_t encode;
+} blackboxGPSFieldDefinition_t;
+
+/**
+ * Description of the blackbox fields we are writing in our main intra (I) and inter (P) frames. This description is
+ * written into the flight log header so the log can be properly interpreted (but these definitions don't actually cause
+ * the encoding to happen, we have to encode the flight log ourselves in write{Inter|Intra}frame() in a way that matches
+ * the encoding we've promised here).
+ */
+static const blackboxMainFieldDefinition_t blackboxMainFields[] = {
+ /* loopIteration doesn't appear in P frames since it always increments */
+ {"loopIteration", UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(INC), .Pencode = FLIGHT_LOG_FIELD_ENCODING_NULL, CONDITION(ALWAYS)},
+ /* Time advances pretty steadily so the P-frame prediction is a straight line */
+ {"time", UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(STRAIGHT_LINE), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"axisP[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"axisP[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"axisP[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ /* I terms get special packed encoding in P frames: */
+ {"axisI[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
+ {"axisI[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
+ {"axisI[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
+ {"axisD[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)},
+ {"axisD[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)},
+ {"axisD[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)},
+ /* rcCommands are encoded together as a group in P-frames: */
+ {"rcCommand[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
+ {"rcCommand[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
+ {"rcCommand[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
+ /* Throttle is always in the range [minthrottle..maxthrottle]: */
+ {"rcCommand[3]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
+
+ {"vbatLatest", UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
+#ifdef MAG
+ {"magADC[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
+ {"magADC[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
+ {"magADC[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
+#endif
+#ifdef BARO
+ {"BaroAlt", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO},
+#endif
+
+ /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
+ {"gyroData[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"gyroData[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"gyroData[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"accSmooth[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"accSmooth[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ {"accSmooth[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
+ /* Motors only rarely drops under minthrottle (when stick falls below mincommand), so predict minthrottle for it and use *unsigned* encoding (which is large for negative numbers but more compact for positive ones): */
+ {"motor[0]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_1)},
+ /* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */
+ {"motor[1]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_2)},
+ {"motor[2]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_3)},
+ {"motor[3]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_4)},
+ {"motor[4]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_5)},
+ {"motor[5]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_6)},
+ {"motor[6]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_7)},
+ {"motor[7]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)},
+ {"servo[5]", UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
+};
+
+#ifdef GPS
+// GPS position/vel frame
+static const blackboxGPSFieldDefinition_t blackboxGpsGFields[] = {
+ {"GPS_numSat", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
+ {"GPS_coord[0]", 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_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}
+};
+
+// GPS home frame
+static const blackboxGPSFieldDefinition_t blackboxGpsHFields[] = {
+ {"GPS_home[0]", SIGNED, PREDICT(0), ENCODING(SIGNED_VB)},
+ {"GPS_home[1]", SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}
+};
+#endif
+
+typedef enum BlackboxState {
+ BLACKBOX_STATE_DISABLED = 0,
+ BLACKBOX_STATE_STOPPED,
+ BLACKBOX_STATE_SEND_HEADER,
+ BLACKBOX_STATE_SEND_FIELDINFO,
+ BLACKBOX_STATE_SEND_GPS_H_HEADERS,
+ BLACKBOX_STATE_SEND_GPS_G_HEADERS,
+ BLACKBOX_STATE_SEND_SYSINFO,
+ BLACKBOX_STATE_PRERUN,
+ BLACKBOX_STATE_RUNNING
+} BlackboxState;
+
+typedef struct gpsState_t {
+ int32_t GPS_home[2], GPS_coord[2];
+ uint8_t GPS_numSat;
+} gpsState_t;
+
+//From mixer.c:
+extern uint8_t motorCount;
+
+//From mw.c:
+extern uint32_t currentTime;
+
+// How many bytes should we transmit per loop iteration?
+static uint8_t serialChunkSize = 16;
+
+static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
+
+static struct {
+ uint32_t headerIndex;
+
+ /* 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 blackboxIteration;
+static uint32_t blackboxPFrameIndex, blackboxIFrameIndex;
+
+static serialPort_t *blackboxPort;
+static portMode_t previousPortMode;
+static uint32_t previousBaudRate;
+
+/*
+ * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
+ * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs
+ * to encode:
+ */
+static uint16_t vbatReference;
+static gpsState_t gpsHistory;
+
+// Keep a history of length 2, plus a buffer for MW to store the new values into
+static blackboxValues_t blackboxHistoryRing[3];
+
+// These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
+static blackboxValues_t* blackboxHistory[3];
+
+static void blackboxWrite(uint8_t value)
+{
+ serialWrite(blackboxPort, value);
+}
+
+static void _putc(void *p, char c)
+{
+ (void)p;
+ serialWrite(blackboxPort, c);
+}
+
+//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!)
+static void blackboxPrintf(char *fmt, ...)
+{
+ va_list va;
+ va_start(va, fmt);
+ tfp_format(NULL, _putc, fmt, va);
+ va_end(va);
+}
+
+// Print the null-terminated string 's' to the serial port and return the number of bytes written
+static int blackboxPrint(const char *s)
+{
+ const char *pos = s;
+
+ while (*pos) {
+ serialWrite(blackboxPort, *pos);
+ pos++;
+ }
+
+ return pos - s;
+}
+
+/**
+ * Write an unsigned integer to the blackbox serial port using variable byte encoding.
+ */
+static void writeUnsignedVB(uint32_t value)
+{
+ //While this isn't the final byte (we can only write 7 bits at a time)
+ while (value > 127) {
+ blackboxWrite((uint8_t) (value | 0x80)); // Set the high bit to mean "more bytes follow"
+ value >>= 7;
+ }
+ blackboxWrite(value);
+}
+
+/**
+ * Write a signed integer to the blackbox serial port using ZigZig and variable byte encoding.
+ */
+static void writeSignedVB(int32_t value)
+{
+ //ZigZag encode to make the value always positive
+ writeUnsignedVB((uint32_t)((value << 1) ^ (value >> 31)));
+}
+
+/**
+ * Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits
+ */
+static void writeTag2_3S32(int32_t *values) {
+ static const int NUM_FIELDS = 3;
+
+ //Need to be enums rather than const ints if we want to switch on them (due to being C)
+ enum {
+ BITS_2 = 0,
+ BITS_4 = 1,
+ BITS_6 = 2,
+ BITS_32 = 3
+ };
+
+ enum {
+ BYTES_1 = 0,
+ BYTES_2 = 1,
+ BYTES_3 = 2,
+ BYTES_4 = 3
+ };
+
+ int x;
+ int selector = BITS_2, selector2;
+
+ /*
+ * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes
+ * below:
+ *
+ * Selector possibilities
+ *
+ * 2 bits per field ss11 2233,
+ * 4 bits per field ss00 1111 2222 3333
+ * 6 bits per field ss11 1111 0022 2222 0033 3333
+ * 32 bits per field sstt tttt followed by fields of various byte counts
+ */
+ for (x = 0; x < NUM_FIELDS; x++) {
+ //Require more than 6 bits?
+ if (values[x] >= 32 || values[x] < -32) {
+ selector = BITS_32;
+ break;
+ }
+
+ //Require more than 4 bits?
+ if (values[x] >= 8 || values[x] < -8) {
+ if (selector < BITS_6)
+ selector = BITS_6;
+ } else if (values[x] >= 2 || values[x] < -2) { //Require more than 2 bits?
+ if (selector < BITS_4)
+ selector = BITS_4;
+ }
+ }
+
+ switch (selector) {
+ case BITS_2:
+ blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03));
+ break;
+ case BITS_4:
+ blackboxWrite((selector << 6) | (values[0] & 0x0F));
+ blackboxWrite((values[1] << 4) | (values[2] & 0x0F));
+ break;
+ case BITS_6:
+ blackboxWrite((selector << 6) | (values[0] & 0x3F));
+ blackboxWrite((uint8_t)values[1]);
+ blackboxWrite((uint8_t)values[2]);
+ break;
+ case BITS_32:
+ /*
+ * Do another round to compute a selector for each field, assuming that they are at least 8 bits each
+ *
+ * Selector2 field possibilities
+ * 0 - 8 bits
+ * 1 - 16 bits
+ * 2 - 24 bits
+ * 3 - 32 bits
+ */
+ selector2 = 0;
+
+ //Encode in reverse order so the first field is in the low bits:
+ for (x = NUM_FIELDS - 1; x >= 0; x--) {
+ selector2 <<= 2;
+
+ if (values[x] < 128 && values[x] >= -128)
+ selector2 |= BYTES_1;
+ else if (values[x] < 32768 && values[x] >= -32768)
+ selector2 |= BYTES_2;
+ else if (values[x] < 8388608 && values[x] >= -8388608)
+ selector2 |= BYTES_3;
+ else
+ selector2 |= BYTES_4;
+ }
+
+ //Write the selectors
+ blackboxWrite((selector << 6) | selector2);
+
+ //And now the values according to the selectors we picked for them
+ for (x = 0; x < NUM_FIELDS; x++, selector2 >>= 2) {
+ switch (selector2 & 0x03) {
+ case BYTES_1:
+ blackboxWrite(values[x]);
+ break;
+ case BYTES_2:
+ blackboxWrite(values[x]);
+ blackboxWrite(values[x] >> 8);
+ break;
+ case BYTES_3:
+ blackboxWrite(values[x]);
+ blackboxWrite(values[x] >> 8);
+ blackboxWrite(values[x] >> 16);
+ break;
+ case BYTES_4:
+ blackboxWrite(values[x]);
+ blackboxWrite(values[x] >> 8);
+ blackboxWrite(values[x] >> 16);
+ blackboxWrite(values[x] >> 24);
+ break;
+ }
+ }
+ break;
+ }
+}
+
+/**
+ * Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits.
+ */
+static void writeTag8_4S16(int32_t *values) {
+
+ //Need to be enums rather than const ints if we want to switch on them (due to being C)
+ enum {
+ FIELD_ZERO = 0,
+ FIELD_4BIT = 1,
+ FIELD_8BIT = 2,
+ FIELD_16BIT = 3
+ };
+
+ uint8_t selector, buffer;
+ int nibbleIndex;
+ int x;
+
+ selector = 0;
+ //Encode in reverse order so the first field is in the low bits:
+ for (x = 3; x >= 0; x--) {
+ selector <<= 2;
+
+ if (values[x] == 0)
+ selector |= FIELD_ZERO;
+ else if (values[x] < 8 && values[x] >= -8)
+ selector |= FIELD_4BIT;
+ else if (values[x] < 128 && values[x] >= -128)
+ selector |= FIELD_8BIT;
+ else
+ selector |= FIELD_16BIT;
+ }
+
+ blackboxWrite(selector);
+
+ nibbleIndex = 0;
+ buffer = 0;
+ for (x = 0; x < 4; x++, selector >>= 2) {
+ switch (selector & 0x03) {
+ case FIELD_ZERO:
+ //No-op
+ break;
+ case FIELD_4BIT:
+ if (nibbleIndex == 0) {
+ //We fill high-bits first
+ buffer = values[x] << 4;
+ nibbleIndex = 1;
+ } else {
+ blackboxWrite(buffer | (values[x] & 0x0F));
+ nibbleIndex = 0;
+ }
+ break;
+ case FIELD_8BIT:
+ if (nibbleIndex == 0)
+ blackboxWrite(values[x]);
+ else {
+ //Write the high bits of the value first (mask to avoid sign extension)
+ blackboxWrite(buffer | ((values[x] >> 4) & 0x0F));
+ //Now put the leftover low bits into the top of the next buffer entry
+ buffer = values[x] << 4;
+ }
+ break;
+ case FIELD_16BIT:
+ if (nibbleIndex == 0) {
+ //Write high byte first
+ blackboxWrite(values[x] >> 8);
+ blackboxWrite(values[x]);
+ } else {
+ //First write the highest 4 bits
+ blackboxWrite(buffer | ((values[x] >> 12) & 0x0F));
+ // Then the middle 8
+ blackboxWrite(values[x] >> 4);
+ //Only the smallest 4 bits are still left to write
+ buffer = values[x] << 4;
+ }
+ break;
+ }
+ }
+ //Anything left over to write?
+ if (nibbleIndex == 1)
+ blackboxWrite(buffer);
+}
+
+/**
+ * Write `valueCount` fields from `values` to the Blackbox using signed variable byte encoding. A 1-byte header is
+ * written first which specifies which fields are non-zero (so this encoding is compact when most fields are zero).
+ *
+ * valueCount must be 8 or less.
+ */
+static void writeTag8_8SVB(int32_t *values, int valueCount)
+{
+ uint8_t header;
+ int i;
+
+ if (valueCount > 0) {
+ //If we're only writing one field then we can skip the header
+ if (valueCount == 1) {
+ writeSignedVB(values[0]);
+ } else {
+ //First write a one-byte header that marks which fields are non-zero
+ header = 0;
+
+ // First field should be in low bits of header
+ for (i = valueCount - 1; i >= 0; i--) {
+ header <<= 1;
+
+ if (values[i] != 0)
+ header |= 0x01;
+ }
+
+ blackboxWrite(header);
+
+ for (i = 0; i < valueCount; i++)
+ if (values[i] != 0)
+ writeSignedVB(values[i]);
+ }
+ }
+}
+
+static bool testBlackboxCondition(FlightLogFieldCondition condition)
+{
+ switch (condition) {
+ case FLIGHT_LOG_FIELD_CONDITION_ALWAYS:
+ return true;
+
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
+ case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
+ return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
+ case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
+ 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_1:
+ case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
+ return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
+
+ case FLIGHT_LOG_FIELD_CONDITION_MAG:
+#ifdef MAG
+ return sensors(SENSOR_MAG);
+#else
+ return false;
+#endif
+
+ case FLIGHT_LOG_FIELD_CONDITION_BARO:
+#ifdef BARO
+ return sensors(SENSOR_BARO);
+#else
+ return false;
+#endif
+
+ case FLIGHT_LOG_FIELD_CONDITION_VBAT:
+ return feature(FEATURE_VBAT);
+
+ case FLIGHT_LOG_FIELD_CONDITION_NEVER:
+ return false;
+ default:
+ return false;
+ }
+}
+
+static void blackboxSetState(BlackboxState newState)
+{
+ //Perform initial setup required for the new state
+ switch (newState) {
+ case BLACKBOX_STATE_SEND_HEADER:
+ xmitState.headerIndex = 0;
+ xmitState.u.startTime = millis();
+ break;
+ case BLACKBOX_STATE_SEND_FIELDINFO:
+ case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
+ case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
+ xmitState.headerIndex = 0;
+ xmitState.u.fieldIndex = -1;
+ break;
+ case BLACKBOX_STATE_SEND_SYSINFO:
+ xmitState.headerIndex = 0;
+ break;
+ case BLACKBOX_STATE_RUNNING:
+ blackboxIteration = 0;
+ blackboxPFrameIndex = 0;
+ blackboxIFrameIndex = 0;
+ break;
+ default:
+ ;
+ }
+ blackboxState = newState;
+}
+
+static void writeIntraframe(void)
+{
+ blackboxValues_t *blackboxCurrent = blackboxHistory[0];
+ int x;
+
+ blackboxWrite('I');
+
+ writeUnsignedVB(blackboxIteration);
+ writeUnsignedVB(blackboxCurrent->time);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->axisPID_P[x]);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->axisPID_I[x]);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x))
+ writeSignedVB(blackboxCurrent->axisPID_D[x]);
+
+ for (x = 0; x < 3; x++)
+ writeSignedVB(blackboxCurrent->rcCommand[x]);
+
+ writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle]
+
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
+ /*
+ * Our voltage is expected to decrease over the course of the flight, so store our difference from
+ * the reference:
+ *
+ * Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
+ */
+ writeUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF);
+ }
+
+#ifdef MAG
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->magADC[x]);
+ }
+#endif
+
+#ifdef BARO
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO))
+ writeSignedVB(blackboxCurrent->BaroAlt);
+#endif
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->gyroData[x]);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->accSmooth[x]);
+
+ //Motors can be below minthrottle when disarmed, but that doesn't happen much
+ writeUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle);
+
+ //Motors tend to be similar to each other
+ for (x = 1; x < motorCount; x++)
+ writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]);
+
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER))
+ writeSignedVB(blackboxHistory[0]->servo[5] - 1500);
+
+ //Rotate our history buffers:
+
+ //The current state becomes the new "before" state
+ blackboxHistory[1] = blackboxHistory[0];
+ //And since we have no other history, we also use it for the "before, before" state
+ blackboxHistory[2] = blackboxHistory[0];
+ //And advance the current state over to a blank space ready to be filled
+ blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
+}
+
+static void writeInterframe(void)
+{
+ int x;
+ int32_t deltas[5];
+
+ blackboxValues_t *blackboxCurrent = blackboxHistory[0];
+ blackboxValues_t *blackboxLast = blackboxHistory[1];
+
+ blackboxWrite('P');
+
+ //No need to store iteration count since its delta is always 1
+
+ /*
+ * Since the difference between the difference between successive times will be nearly zero, use
+ * second-order differences.
+ */
+ writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time));
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxCurrent->axisPID_P[x] - blackboxLast->axisPID_P[x]);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ deltas[x] = blackboxCurrent->axisPID_I[x] - blackboxLast->axisPID_I[x];
+
+ /*
+ * The PID I field changes very slowly, most of the time +-2, so use an encoding
+ * that can pack all three fields into one byte in that situation.
+ */
+ writeTag2_3S32(deltas);
+
+ /*
+ * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
+ * always zero. So don't bother recording D results when PID D terms are zero.
+ */
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x))
+ writeSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]);
+
+ /*
+ * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
+ * can pack multiple values per byte:
+ */
+ for (x = 0; x < 4; x++)
+ deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x];
+
+ writeTag8_4S16(deltas);
+
+ //Check for sensors that are updated periodically (so deltas are normally zero) VBAT, MAG, BARO
+ int optionalFieldCount = 0;
+
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
+ deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest;
+ }
+
+#ifdef MAG
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
+ }
+#endif
+
+#ifdef BARO
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO))
+ deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt;
+#endif
+ writeTag8_8SVB(deltas, optionalFieldCount);
+
+ //Since gyros, accs and motors are noisy, base the prediction on the average of the history:
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2);
+
+ for (x = 0; x < XYZ_AXIS_COUNT; x++)
+ writeSignedVB(blackboxHistory[0]->accSmooth[x] - (blackboxHistory[1]->accSmooth[x] + blackboxHistory[2]->accSmooth[x]) / 2);
+
+ for (x = 0; x < motorCount; x++)
+ writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2);
+
+ if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER))
+ writeSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]);
+
+ //Rotate our history buffers
+ blackboxHistory[2] = blackboxHistory[1];
+ blackboxHistory[1] = blackboxHistory[0];
+ blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
+}
+
+static int gcd(int num, int denom)
+{
+ if (denom == 0)
+ return num;
+ return gcd(denom, num % denom);
+}
+
+static void validateBlackboxConfig()
+{
+ int div;
+
+ if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0
+ || masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
+ masterConfig.blackbox_rate_num = 1;
+ masterConfig.blackbox_rate_denom = 1;
+ } else {
+ div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
+
+ masterConfig.blackbox_rate_num /= div;
+ masterConfig.blackbox_rate_denom /= div;
+ }
+}
+
+static void configureBlackboxPort(void)
+{
+ blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX);
+ if (blackboxPort) {
+ previousPortMode = blackboxPort->mode;
+ previousBaudRate = blackboxPort->baudRate;
+
+ serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE);
+ serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE);
+ beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
+ } else {
+ blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
+
+ if (blackboxPort) {
+ previousPortMode = blackboxPort->mode;
+ 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)
+{
+ serialSetMode(blackboxPort, previousPortMode);
+ serialSetBaudRate(blackboxPort, previousBaudRate);
+
+ endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
+}
+
+void startBlackbox(void)
+{
+ if (blackboxState == BLACKBOX_STATE_STOPPED) {
+ validateBlackboxConfig();
+
+ configureBlackboxPort();
+
+ if (!blackboxPort) {
+ blackboxSetState(BLACKBOX_STATE_DISABLED);
+ return;
+ }
+
+ memset(&gpsHistory, 0, sizeof(gpsHistory));
+
+ blackboxHistory[0] = &blackboxHistoryRing[0];
+ blackboxHistory[1] = &blackboxHistoryRing[1];
+ blackboxHistory[2] = &blackboxHistoryRing[2];
+
+ vbatReference = vbatLatest;
+
+ //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
+
+ blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
+ }
+}
+
+void finishBlackbox(void)
+{
+ if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) {
+ blackboxSetState(BLACKBOX_STATE_STOPPED);
+
+ releaseBlackboxPort();
+ }
+}
+
+#ifdef GPS
+static void writeGPSHomeFrame()
+{
+ blackboxWrite('H');
+
+ writeSignedVB(GPS_home[0]);
+ writeSignedVB(GPS_home[1]);
+ //TODO it'd be great if we could grab the GPS current time and write that too
+
+ gpsHistory.GPS_home[0] = GPS_home[0];
+ gpsHistory.GPS_home[1] = GPS_home[1];
+}
+
+static void writeGPSFrame()
+{
+ blackboxWrite('G');
+
+ writeUnsignedVB(GPS_numSat);
+ writeSignedVB(GPS_coord[0] - gpsHistory.GPS_home[0]);
+ writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]);
+ writeUnsignedVB(GPS_altitude);
+ writeUnsignedVB(GPS_speed);
+
+ gpsHistory.GPS_numSat = GPS_numSat;
+ gpsHistory.GPS_coord[0] = GPS_coord[0];
+ gpsHistory.GPS_coord[1] = GPS_coord[1];
+}
+#endif
+
+/**
+ * Fill the current state of the blackbox using values read from the flight controller
+ */
+static void loadBlackboxState(void)
+{
+ blackboxValues_t *blackboxCurrent = blackboxHistory[0];
+ int i;
+
+ blackboxCurrent->time = currentTime;
+
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->axisPID_P[i] = axisPID_P[i];
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->axisPID_I[i] = axisPID_I[i];
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->axisPID_D[i] = axisPID_D[i];
+
+ for (i = 0; i < 4; i++)
+ blackboxCurrent->rcCommand[i] = rcCommand[i];
+
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->gyroData[i] = gyroData[i];
+
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->accSmooth[i] = accSmooth[i];
+
+ for (i = 0; i < motorCount; i++)
+ blackboxCurrent->motor[i] = motor[i];
+
+ blackboxCurrent->vbatLatest = vbatLatest;
+
+#ifdef MAG
+ for (i = 0; i < XYZ_AXIS_COUNT; i++)
+ blackboxCurrent->magADC[i] = magADC[i];
+#endif
+
+#ifdef BARO
+ blackboxCurrent->BaroAlt = BaroAlt;
+#endif
+
+ //Tail servo for tricopters
+ blackboxCurrent->servo[5] = servo[5];
+}
+
+/**
+ * Transmit the header information for the given field definitions. Transmitted header lines look like:
+ *
+ * H Field I name:a,b,c
+ * H Field I predictor:0,1,2
+ *
+ * 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.
+ *
+ * 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
+ * fieldDefinition and secondCondition arrays.
+ *
+ * Returns true if there is still header left to transmit (so call again to continue transmission).
+ */
+static bool sendFieldDefinition(const char * const *headerNames, unsigned int headerCount, const void *fieldDefinitions,
+ const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
+{
+ const blackboxFieldDefinition_t *def;
+ int charsWritten;
+ static bool needComma = false;
+ size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
+ size_t conditionsStride = (char*) secondCondition - (char*) conditions;
+
+ /*
+ * 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.
+ */
+ if (xmitState.u.fieldIndex == -1) {
+ if (xmitState.headerIndex >= headerCount)
+ return false; //Someone probably called us again after we had already completed transmission
+
+ charsWritten = blackboxPrint("H Field ");
+ charsWritten += blackboxPrint(headerNames[xmitState.headerIndex]);
+ charsWritten += blackboxPrint(":");
+
+ xmitState.u.fieldIndex++;
+ needComma = false;
+ } else
+ charsWritten = 0;
+
+ for (; xmitState.u.fieldIndex < fieldCount && charsWritten < serialChunkSize; xmitState.u.fieldIndex++) {
+ def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
+
+ if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
+ if (needComma) {
+ blackboxWrite(',');
+ charsWritten++;
+ } else
+ needComma = true;
+
+ // The first header is a field name
+ if (xmitState.headerIndex == 0) {
+ charsWritten += blackboxPrint(def->name);
+ } else {
+ //The other headers are integers
+ if (def->arr[xmitState.headerIndex - 1] >= 10) {
+ blackboxWrite(def->arr[xmitState.headerIndex - 1] / 10 + '0');
+ blackboxWrite(def->arr[xmitState.headerIndex - 1] % 10 + '0');
+ charsWritten += 2;
+ } else {
+ blackboxWrite(def->arr[xmitState.headerIndex - 1] + '0');
+ charsWritten++;
+ }
+ }
+ }
+ }
+
+ // Did we complete this line?
+ if (xmitState.u.fieldIndex == fieldCount) {
+ blackboxWrite('\n');
+ xmitState.headerIndex++;
+ xmitState.u.fieldIndex = -1;
+ }
+
+ return xmitState.headerIndex < headerCount;
+}
+
+/**
+ * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
+ * true iff transmission is complete, otherwise call again later to continue transmission.
+ */
+static bool blackboxWriteSysinfo()
+{
+ union floatConvert_t {
+ float f;
+ uint32_t u;
+ } floatConvert;
+
+ 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:
+ //Shouldn't ever get here
+ break;
+ case 1:
+ blackboxPrintf("H Firmware type:Cleanflight\n");
+
+ xmitState.u.serialBudget -= strlen("H Firmware type:Cleanflight\n");
+ break;
+ case 2:
+ 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;
+ case 3:
+ blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
+
+ xmitState.u.serialBudget -= strlen("H Firmware date:%s %s\n") + strlen(buildDate) + strlen(buildTime);
+ break;
+ case 4:
+ 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;
+ case 5:
+ blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
+
+ xmitState.u.serialBudget -= strlen("H rcRate:%d\n");
+ break;
+ case 6:
+ blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
+
+ xmitState.u.serialBudget -= strlen("H minthrottle:%d\n");
+ break;
+ case 7:
+ blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
+
+ xmitState.u.serialBudget -= strlen("H maxthrottle:%d\n");
+ break;
+ case 8:
+ floatConvert.f = gyro.scale;
+ 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;
+ case 11:
+ blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
+ masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
+
+ xmitState.u.serialBudget -= strlen("H vbatcellvoltage:%u,%u,%u\n");
+ break;
+ case 12:
+ blackboxPrintf("H vbatref:%u\n", vbatReference);
+
+ xmitState.u.serialBudget -= strlen("H vbatref:%u\n");
+ break;
+ default:
+ return true;
+ }
+
+ xmitState.headerIndex++;
+ return false;
+}
+
+// Beep the buzzer and write the current time to the log as a synchronization point
+static void blackboxPlaySyncBeep()
+{
+ uint32_t now = micros();
+
+ /*
+ * The regular beep routines aren't going to work for us, because they queue up the beep to be executed later.
+ * Our beep is timing sensitive, so start beeping now without setting the beeperIsOn flag.
+ */
+ BEEP_ON;
+
+ // Have the regular beeper code turn off the beep for us eventually, since that's not timing-sensitive
+ queueConfirmationBeep(1);
+
+ blackboxWrite('E');
+ blackboxWrite(FLIGHT_LOG_EVENT_SYNC_BEEP);
+
+ writeUnsignedVB(now);
+}
+
+void handleBlackbox(void)
+{
+ int i;
+
+ switch (blackboxState) {
+ case BLACKBOX_STATE_SEND_HEADER:
+ //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
+ * buffer.
+ */
+ if (millis() > xmitState.u.startTime + 100) {
+ for (i = 0; i < serialChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++)
+ blackboxWrite(blackboxHeader[xmitState.headerIndex]);
+
+ if (blackboxHeader[xmitState.headerIndex] == '\0')
+ blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO);
+ }
+ break;
+ case BLACKBOX_STATE_SEND_FIELDINFO:
+ //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
+ if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1,
+ ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
+#ifdef GPS
+ if (feature(FEATURE_GPS))
+ blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADERS);
+ else
+#endif
+ blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
+ }
+ break;
+#ifdef GPS
+ case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
+ //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
+ if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1,
+ ARRAY_LENGTH(blackboxGpsHFields), NULL, NULL)) {
+ blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS);
+ }
+ break;
+ case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
+ //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
+ if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1,
+ ARRAY_LENGTH(blackboxGpsGFields), NULL, NULL)) {
+ blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
+ }
+ break;
+#endif
+ case BLACKBOX_STATE_SEND_SYSINFO:
+ //On entry of this state, xmitState.headerIndex is 0
+
+ //Keep writing chunks of the system info headers until it returns true to signal completion
+ if (blackboxWriteSysinfo())
+ blackboxSetState(BLACKBOX_STATE_PRERUN);
+ break;
+ case BLACKBOX_STATE_PRERUN:
+ blackboxPlaySyncBeep();
+
+ blackboxSetState(BLACKBOX_STATE_RUNNING);
+ break;
+ case BLACKBOX_STATE_RUNNING:
+ // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
+
+ // Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
+ if (blackboxPFrameIndex == 0) {
+ // Copy current system values into the blackbox
+ loadBlackboxState();
+ writeIntraframe();
+ } else {
+ if ((blackboxPFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) {
+ loadBlackboxState();
+ writeInterframe();
+ }
+#ifdef GPS
+ if (feature(FEATURE_GPS)) {
+ /*
+ * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
+ * GPS home position.
+ *
+ * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
+ * still be interpreted correctly.
+ */
+ if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
+ || (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
+
+ writeGPSHomeFrame();
+ writeGPSFrame();
+ } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0]
+ || GPS_coord[1] != gpsHistory.GPS_coord[1]) {
+ //We could check for velocity changes as well but I doubt it changes independent of position
+ writeGPSFrame();
+ }
+ }
+#endif
+ }
+
+ blackboxIteration++;
+ blackboxPFrameIndex++;
+
+ if (blackboxPFrameIndex == BLACKBOX_I_INTERVAL) {
+ blackboxPFrameIndex = 0;
+ blackboxIFrameIndex++;
+ }
+ break;
+ default:
+ break;
+ }
+}
+
+static bool canUseBlackboxWithCurrentConfiguration(void)
+{
+ if (!feature(FEATURE_BLACKBOX))
+ return false;
+
+ return true;
+}
+
+void initBlackbox(void)
+{
+ if (canUseBlackboxWithCurrentConfiguration())
+ blackboxSetState(BLACKBOX_STATE_STOPPED);
+ else
+ blackboxSetState(BLACKBOX_STATE_DISABLED);
+}
diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h
new file mode 100644
index 0000000000..5d30671bbf
--- /dev/null
+++ b/src/main/blackbox/blackbox.h
@@ -0,0 +1,47 @@
+/*
+ * 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 .
+ */
+
+#pragma once
+
+#include "common/axis.h"
+#include
+
+typedef struct blackboxValues_t {
+ uint32_t time;
+
+ int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
+
+ int16_t rcCommand[4];
+ int16_t gyroData[XYZ_AXIS_COUNT];
+ int16_t accSmooth[XYZ_AXIS_COUNT];
+ int16_t motor[MAX_SUPPORTED_MOTORS];
+ int16_t servo[MAX_SUPPORTED_SERVOS];
+
+ uint16_t vbatLatest;
+
+#ifdef BARO
+ int32_t BaroAlt;
+#endif
+#ifdef MAG
+ int16_t magADC[XYZ_AXIS_COUNT];
+#endif
+} blackboxValues_t;
+
+void initBlackbox(void);
+void handleBlackbox(void);
+void startBlackbox(void);
+void finishBlackbox(void);
diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h
new file mode 100644
index 0000000000..87db8ecbbb
--- /dev/null
+++ b/src/main/blackbox/blackbox_fielddefs.h
@@ -0,0 +1,100 @@
+/*
+ * 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 .
+ */
+
+#pragma once
+
+typedef enum FlightLogFieldCondition {
+ FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
+ FLIGHT_LOG_FIELD_CONDITION_TRICOPTER,
+
+ FLIGHT_LOG_FIELD_CONDITION_MAG = 20,
+ FLIGHT_LOG_FIELD_CONDITION_BARO,
+ 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_1,
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
+
+ FLIGHT_LOG_FIELD_CONDITION_NEVER = 255,
+} FlightLogFieldCondition;
+
+typedef enum FlightLogFieldPredictor {
+ //No prediction:
+ FLIGHT_LOG_FIELD_PREDICTOR_0 = 0,
+
+ //Predict that the field is the same as last frame:
+ FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1,
+
+ //Predict that the slope between this field and the previous item is the same as that between the past two history items:
+ FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2,
+
+ //Predict that this field is the same as the average of the last two history items:
+ FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3,
+
+ //Predict that this field is minthrottle
+ FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4,
+
+ //Predict that this field is the same as motor 0
+ FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5,
+
+ //This field always increments
+ FLIGHT_LOG_FIELD_PREDICTOR_INC = 6,
+
+ //Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set)
+ FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7,
+
+ //Predict 1500
+ FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8,
+
+ //Predict vbatref, the reference ADC level stored in the header
+ FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9
+
+} FlightLogFieldPredictor;
+
+typedef enum FlightLogFieldEncoding {
+ FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte
+ FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte
+ FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6,
+ FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7,
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8,
+ FLIGHT_LOG_FIELD_ENCODING_NULL = 9 // Nothing is written to the file, take value to be zero
+} FlightLogFieldEncoding;
+
+typedef enum FlightLogFieldSign {
+ FLIGHT_LOG_FIELD_UNSIGNED = 0,
+ FLIGHT_LOG_FIELD_SIGNED = 1
+} FlightLogFieldSign;
+
+typedef enum FlightLogEvent {
+ FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
+ FLIGHT_LOG_EVENT_LOG_END = 255
+} FlightLogEvent;
diff --git a/src/main/config/config.c b/src/main/config/config.c
index 938613caaf..f4b0dca420 100644
--- a/src/main/config/config.c
+++ b/src/main/config/config.c
@@ -445,6 +445,11 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif
+#ifdef BLACKBOX
+ masterConfig.blackbox_rate_num = 1;
+ masterConfig.blackbox_rate_denom = 1;
+#endif
+
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
featureSet(FEATURE_RX_SERIAL);
diff --git a/src/main/config/config.h b/src/main/config/config.h
index bbbc9e7949..351fc1e84b 100644
--- a/src/main/config/config.h
+++ b/src/main/config/config.h
@@ -40,7 +40,8 @@ typedef enum {
FEATURE_RSSI_ADC = 1 << 15,
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
- FEATURE_ONESHOT125 = 1 << 18
+ FEATURE_ONESHOT125 = 1 << 18,
+ FEATURE_BLACKBOX = 1 << 19
} features_e;
bool feature(uint32_t mask);
diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h
index f5575be0c8..bacb7b5a7b 100644
--- a/src/main/config/config_master.h
+++ b/src/main/config/config_master.h
@@ -85,6 +85,8 @@ typedef struct master_t {
uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
+ uint8_t blackbox_rate_num;
+ uint8_t blackbox_rate_denom;
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
diff --git a/src/main/drivers/light_led.h b/src/main/drivers/light_led.h
index 2d3d61bcd9..8f62bd5ab6 100644
--- a/src/main/drivers/light_led.h
+++ b/src/main/drivers/light_led.h
@@ -48,4 +48,20 @@
#define LED1_ON
#endif
+
+#ifdef LED2
+#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN);
+#ifndef LED2_INVERTED
+#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN);
+#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN);
+#else
+#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN);
+#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN);
+#endif // inverted
+#else
+#define LED2_TOGGLE
+#define LED2_OFF
+#define LED2_ON
+#endif
+
void ledInit(void);
diff --git a/src/main/drivers/light_led_stm32f10x.c b/src/main/drivers/light_led_stm32f10x.c
index 991831283f..45fc55d466 100644
--- a/src/main/drivers/light_led_stm32f10x.c
+++ b/src/main/drivers/light_led_stm32f10x.c
@@ -46,6 +46,12 @@ void ledInit(void)
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
+ },
+#endif
+#ifdef LED2
+ {
+ .gpio = LED2_GPIO,
+ .cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};
@@ -58,9 +64,13 @@ void ledInit(void)
#ifdef LED1
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
#endif
+#ifdef LED2
+ RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE);
+#endif
LED0_OFF;
LED1_OFF;
+ LED2_OFF;
for (i = 0; i < gpio_count; i++) {
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c
index 49e8eae128..8908dda081 100644
--- a/src/main/drivers/light_ws2811strip_stm32f30x.c
+++ b/src/main/drivers/light_ws2811strip_stm32f30x.c
@@ -26,10 +26,16 @@
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
-#define WS2811_GPIO GPIOB
-#define WS2811_PIN Pin_8 // TIM16_CH1
-#define WS2811_PERIPHERAL RCC_AHBPeriph_GPIOB
-
+#ifndef WS2811_GPIO
+#define WS2811_GPIO GPIOB
+#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
+#define WS2811_PIN 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)
{
@@ -40,19 +46,20 @@ void ws2811LedStripHardwareInit(void)
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, GPIO_AF_1);
- /* GPIOA Configuration: TIM16 Channel 1 as alternate function push-pull */
+ /* Configuration alternate function push-pull */
GPIO_InitStructure.GPIO_Pin = WS2811_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(WS2811_GPIO, &GPIO_InitStructure);
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM16, ENABLE);
+ RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE);
/* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
/* Time base configuration */
@@ -60,27 +67,27 @@ void ws2811LedStripHardwareInit(void)
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
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_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 0;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
- TIM_OC1Init(TIM16, &TIM_OCInitStructure);
- TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
+ TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
+ TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
- TIM_CtrlPWMOutputs(TIM16, ENABLE);
+ TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
/* configure DMA */
/* DMA clock enable */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
/* DMA1 Channel Config */
- DMA_DeInit(DMA1_Channel3);
+ DMA_DeInit(WS2811_DMA_CHANNEL);
- DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM16->CCR1;
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
@@ -92,16 +99,15 @@ void ws2811LedStripHardwareInit(void)
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
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(TIM16, TIM_DMA_CC1, ENABLE);
+ TIM_DMACmd(WS2811_TIMER, 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_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_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
@@ -115,17 +121,28 @@ void DMA1_Channel3_IRQHandler(void)
{
if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) {
ws2811LedDataTransferInProgress = 0;
- DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel 6
- DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel 6 transfer complete flag
+ DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel
+ DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel transfer complete flag
}
}
+#if 0
+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)
{
- DMA_SetCurrDataCounter(DMA1_Channel3, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
- TIM_SetCounter(TIM16, 0);
- TIM_Cmd(TIM16, ENABLE);
- DMA_Cmd(DMA1_Channel3, ENABLE);
+ DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
+ TIM_SetCounter(WS2811_TIMER, 0);
+ TIM_Cmd(WS2811_TIMER, ENABLE);
+ DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
}
diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c
index 85bbe09dbf..67a01b2b47 100644
--- a/src/main/drivers/pwm_mapping.c
+++ b/src/main/drivers/pwm_mapping.c
@@ -334,8 +334,15 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#ifdef LED_STRIP_TIMER
// skip LED Strip output
- if (init->useLEDStrip && timerHardwarePtr->tim == LED_STRIP_TIMER)
- continue;
+ if (init->useLEDStrip) {
+ if (timerHardwarePtr->tim == LED_STRIP_TIMER)
+ continue;
+#if defined(WS2811_GPIO) && defined(WS2811_PIN)
+ if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->pin == WS2811_PIN)
+ continue;
+#endif
+ }
+
#endif
#ifdef STM32F10X
diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c
index d32119d926..354ce06dd3 100644
--- a/src/main/drivers/serial_uart_stm32f30x.c
+++ b/src/main/drivers/serial_uart_stm32f30x.c
@@ -326,6 +326,7 @@ void DMA1_Channel4_IRQHandler(void)
handleUsartTxDma(s);
}
+#ifdef USE_USART2_TX_DMA
// USART2 Tx DMA Handler
void DMA1_Channel7_IRQHandler(void)
{
@@ -334,6 +335,7 @@ void DMA1_Channel7_IRQHandler(void)
DMA_Cmd(DMA1_Channel7, DISABLE);
handleUsartTxDma(s);
}
+#endif
// USART3 Tx DMA Handler
void DMA1_Channel2_IRQHandler(void)
diff --git a/src/main/flight/flight.c b/src/main/flight/flight.c
index 22ee35fc93..c5942b05ca 100644
--- a/src/main/flight/flight.c
+++ b/src/main/flight/flight.c
@@ -45,6 +45,11 @@ extern uint16_t cycleTime;
int16_t heading, magHold;
int16_t axisPID[3];
+
+#ifdef BLACKBOX
+int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
+#endif
+
uint8_t dynP8[3], dynI8[3], dynD8[3];
static int32_t errorGyroI[3] = { 0, 0, 0 };
@@ -247,6 +252,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
delta1[axis] = delta;
DTerm = (deltaSum * dynD8[axis]) / 32;
axisPID[axis] = PTerm + ITerm - DTerm;
+
+#ifdef BLACKBOX
+ axisPID_P[axis] = PTerm;
+ axisPID_I[axis] = ITerm;
+ axisPID_D[axis] = -DTerm;
+#endif
}
}
@@ -330,6 +341,12 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
// -----calculate total PID output
axisPID[axis] = PTerm + ITerm + DTerm;
+
+#ifdef BLACKBOX
+ axisPID_P[axis] = PTerm;
+ axisPID_I[axis] = ITerm;
+ axisPID_D[axis] = DTerm;
+#endif
}
}
diff --git a/src/main/flight/flight.h b/src/main/flight/flight.h
index a6fadf55f6..158ac23a79 100644
--- a/src/main/flight/flight.h
+++ b/src/main/flight/flight.h
@@ -127,6 +127,8 @@ extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AX
extern int32_t accSum[XYZ_AXIS_COUNT];
extern int16_t axisPID[XYZ_AXIS_COUNT];
+extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
+
extern int16_t heading, magHold;
extern int32_t AltHold;
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index 16037d1651..324bdf12fc 100644
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -47,7 +47,7 @@
#define AUX_FORWARD_CHANNEL_TO_SERVO_COUNT 4
-static uint8_t motorCount = 0;
+uint8_t motorCount = 0;
int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index a058941898..185ecf51c5 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -62,7 +62,10 @@ const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUN
SCENARIO_CLI_ONLY,
SCENARIO_GPS_PASSTHROUGH_ONLY,
SCENARIO_MSP_ONLY,
- SCENARIO_SMARTPORT_TELEMETRY_ONLY
+ SCENARIO_SMARTPORT_TELEMETRY_ONLY,
+
+ SCENARIO_BLACKBOX_ONLY,
+ SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH
};
static serialConfig_t *serialConfig;
@@ -136,7 +139,8 @@ const functionConstraint_t functionConstraints[] = {
{ FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
{ FUNCTION_SERIAL_RX, 9600, 115200, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
{ FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE },
- { FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE }
+ { FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE },
+ { FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE }
};
#define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
diff --git a/src/main/io/serial.h b/src/main/io/serial.h
index 854044421f..db685a3271 100644
--- a/src/main/io/serial.h
+++ b/src/main/io/serial.h
@@ -25,7 +25,8 @@ typedef enum {
FUNCTION_SMARTPORT_TELEMETRY = (1 << 3),
FUNCTION_SERIAL_RX = (1 << 4),
FUNCTION_GPS = (1 << 5),
- FUNCTION_GPS_PASSTHROUGH = (1 << 6)
+ FUNCTION_GPS_PASSTHROUGH = (1 << 6),
+ FUNCTION_BLACKBOX = (1 << 7)
} serialPortFunction_e;
typedef enum {
@@ -52,10 +53,12 @@ typedef enum {
SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH,
SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX,
SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY,
- SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY
+ SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY,
+ SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX,
+ SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH
} serialPortFunctionScenario_e;
-#define SERIAL_PORT_SCENARIO_COUNT 10
+#define SERIAL_PORT_SCENARIO_COUNT 12
#define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c
index 2628ba93a7..428496c159 100644
--- a/src/main/io/serial_cli.c
+++ b/src/main/io/serial_cli.c
@@ -135,7 +135,8 @@ static const char * const featureNames[] = {
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
- "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", NULL
+ "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
+ "BLACKBOX", NULL
};
// sync this with sensors_e
@@ -404,6 +405,9 @@ const clivalue_t valueTable[] = {
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
+
+ { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
+ { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
};
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c
index b43409bf54..8943c4453d 100644
--- a/src/main/io/serial_msp.c
+++ b/src/main/io/serial_msp.c
@@ -121,7 +121,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define MSP_PROTOCOL_VERSION 0
#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
@@ -1097,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
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++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET);
@@ -1145,10 +1145,16 @@ static bool processInCommand(void)
magHold = read16();
break;
case MSP_SET_RAW_RC:
- // FIXME need support for more than 8 channels
- for (i = 0; i < 8; i++)
- rcData[i] = read16();
- rxMspFrameRecieve();
+ {
+ uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
+ if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
+ headSerialError(0);
+ } else {
+ for (i = 0; i < channelCount; i++)
+ rcData[i] = read16();
+ rxMspFrameRecieve();
+ }
+ }
break;
case MSP_SET_ACC_TRIM:
currentProfile->accelerometerTrims.values.pitch = read16();
@@ -1435,22 +1441,29 @@ static bool processInCommand(void)
break;
case MSP_SET_LED_STRIP_CONFIG:
- 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;
+ {
+ uint8_t ledCount = currentPort->dataSize / 6;
+ if (ledCount != MAX_LED_STRIP_LENGTH) {
+ headSerialError(0);
+ break;
+ }
+ 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();
- ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
+ mask = read16();
+ ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
- mask = read8();
- ledConfig->xy = CALCULATE_LED_X(mask);
+ mask = read8();
+ ledConfig->xy = CALCULATE_LED_X(mask);
- mask = read8();
- ledConfig->xy |= CALCULATE_LED_Y(mask);
+ mask = read8();
+ ledConfig->xy |= CALCULATE_LED_Y(mask);
+ }
}
break;
#endif
diff --git a/src/main/main.c b/src/main/main.c
index 9b06fd39f5..4a9656b8df 100644
--- a/src/main/main.c
+++ b/src/main/main.c
@@ -66,6 +66,7 @@
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "telemetry/telemetry.h"
+#include "blackbox/blackbox.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "config/runtime_config.h"
@@ -73,8 +74,8 @@
#include "config/config_profile.h"
#include "config/config_master.h"
-#ifdef NAZE
-#include "target/NAZE/hardware_revision.h"
+#ifdef USE_HARDWARE_REVISION_DETECTION
+#include "hardware_revision.h"
#endif
#include "build_config.h"
@@ -145,13 +146,15 @@ void init(void)
SetSysClock(masterConfig.emf_avoidance);
#endif
-#ifdef NAZE
+#ifdef USE_HARDWARE_REVISION_DETECTION
detectHardwareRevision();
#endif
systemInit();
-#ifdef SPEKTRUM_BIND
+ ledInit();
+
+ #ifdef SPEKTRUM_BIND
if (feature(FEATURE_RX_SERIAL)) {
switch (masterConfig.rxConfig.serialrx_provider) {
case SERIALRX_SPEKTRUM1024:
@@ -169,8 +172,6 @@ void init(void)
timerInit(); // timer must be initialized before any channel is allocated
- ledInit();
-
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioMode = Mode_Out_OD,
@@ -200,7 +201,7 @@ void init(void)
spiInit(SPI2);
#endif
-#ifdef NAZE
+#ifdef USE_HARDWARE_REVISION_DETECTION
updateHardwareRevision();
#endif
@@ -344,6 +345,10 @@ void init(void)
initTelemetry();
#endif
+#ifdef BLACKBOX
+ initBlackbox();
+#endif
+
previousTime = micros();
if (masterConfig.mixerMode == MIXER_GIMBAL) {
@@ -385,6 +390,10 @@ void init(void)
#endif
}
#endif
+
+#ifdef CJMCU
+ LED2_ON;
+#endif
}
#ifdef SOFTSERIAL_LOOPBACK
diff --git a/src/main/mw.c b/src/main/mw.c
index 54defd191e..fff9470b8d 100644
--- a/src/main/mw.c
+++ b/src/main/mw.c
@@ -67,6 +67,7 @@
#include "io/statusindicator.h"
#include "rx/msp.h"
#include "telemetry/telemetry.h"
+#include "blackbox/blackbox.h"
#include "config/runtime_config.h"
#include "config/config.h"
@@ -306,6 +307,15 @@ void mwDisarm(void)
}
}
#endif
+
+#ifdef BLACKBOX
+ if (feature(FEATURE_BLACKBOX)) {
+ finishBlackbox();
+ if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
+ mspAllocateSerialPorts(&masterConfig.serialConfig);
+ }
+ }
+#endif
}
}
@@ -327,6 +337,16 @@ void mwArm(void)
}
}
#endif
+
+#ifdef BLACKBOX
+ if (feature(FEATURE_BLACKBOX)) {
+ serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
+ if (sharedBlackboxAndMspPort) {
+ mspReleasePortIfAllocated(sharedBlackboxAndMspPort);
+ }
+ startBlackbox();
+ }
+#endif
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
return;
@@ -539,17 +559,17 @@ void processRx(void)
DISABLE_FLIGHT_MODE(ANGLE_MODE); // failsafe support
}
- if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
+ if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
- DISABLE_FLIGHT_MODE(ANGLE_MODE);
+ DISABLE_FLIGHT_MODE(ANGLE_MODE);
- if (!FLIGHT_MODE(HORIZON_MODE)) {
- resetErrorAngle();
- ENABLE_FLIGHT_MODE(HORIZON_MODE);
- }
- } else {
- DISABLE_FLIGHT_MODE(HORIZON_MODE);
- }
+ if (!FLIGHT_MODE(HORIZON_MODE)) {
+ resetErrorAngle();
+ ENABLE_FLIGHT_MODE(HORIZON_MODE);
+ }
+ } else {
+ DISABLE_FLIGHT_MODE(HORIZON_MODE);
+ }
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
LED1_ON;
@@ -698,6 +718,12 @@ void loop(void)
mixTable();
writeServos();
writeMotors();
+
+#ifdef BLACKBOX
+ if (!cliMode && feature(FEATURE_BLACKBOX)) {
+ handleBlackbox();
+ }
+#endif
}
#ifdef TELEMETRY
diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c
index 60ebc97263..8e4bda1e85 100644
--- a/src/main/rx/rx.c
+++ b/src/main/rx/rx.c
@@ -265,6 +265,10 @@ void processRxChannels(void)
{
uint8_t chan;
+ if (feature(FEATURE_RX_MSP)) {
+ return; // rcData will have already been updated by MSP_SET_RAW_RC
+ }
+
bool shouldCheckPulse = true;
if (feature(FEATURE_FAILSAFE) && feature(FEATURE_RX_PPM)) {
@@ -341,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
for (c = input; *c; c++) {
s = strchr(rcChannelLetters, *c);
- if (s)
+ if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
rxConfig->rcmap[s - rcChannelLetters] = c - input;
}
}
diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c
index d933c3ce25..5b78dfd208 100644
--- a/src/main/rx/spektrum.c
+++ b/src/main/rx/spektrum.c
@@ -24,6 +24,8 @@
#include "drivers/gpio.h"
#include "drivers/system.h"
+#include "drivers/light_led.h"
+
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
@@ -176,11 +178,12 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
void spektrumBind(rxConfig_t *rxConfig)
{
int i;
-
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
return;
}
+ LED1_ON;
+
gpio_config_t cfg = {
BIND_PIN,
Mode_Out_OD,
@@ -193,16 +196,22 @@ void spektrumBind(rxConfig_t *rxConfig)
// Bind window is around 20-140ms after powerup
delay(60);
+ LED1_OFF;
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
+ LED0_OFF;
+ LED2_OFF;
// RX line, drive low for 120us
digitalLo(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
+ LED0_ON;
+ LED2_ON;
// RX line, drive high for 120us
digitalHi(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
+
}
#ifndef HARDWARE_BIND_PLUG
diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c
index 186c6804e7..9766d40130 100644
--- a/src/main/sensors/battery.c
+++ b/src/main/sensors/battery.c
@@ -31,6 +31,7 @@ uint16_t batteryWarningVoltage;
uint16_t batteryCriticalVoltage;
uint8_t vbat = 0; // battery voltage in 0.1V steps
+uint16_t vbatLatest = 0; // most recent unsmoothed raw reading from vbat adc
int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
@@ -54,7 +55,7 @@ void updateBatteryVoltage(void)
uint16_t vbatSampleTotal = 0;
// store the battery voltage with some other recent battery voltage readings
- vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = adcGetChannel(ADC_BATTERY);
+ vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = vbatLatest = adcGetChannel(ADC_BATTERY);
// calculate vbat based on the average of recent readings
for (index = 0; index < BATTERY_SAMPLE_COUNT; index++) {
diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h
index 6288f9f108..f90395f5fc 100644
--- a/src/main/sensors/battery.h
+++ b/src/main/sensors/battery.h
@@ -42,6 +42,7 @@ typedef enum {
} batteryState_e;
extern uint8_t vbat;
+extern uint16_t vbatLatest;
extern uint8_t batteryCellCount;
extern uint16_t batteryWarningVoltage;
extern int32_t amperage;
diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h
index 44acf46300..3ae21223b3 100644
--- a/src/main/target/CC3D/target.h
+++ b/src/main/target/CC3D/target.h
@@ -77,6 +77,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h
index 3a28e955c9..f4bc202a54 100644
--- a/src/main/target/CHEBUZZF3/target.h
+++ b/src/main/target/CHEBUZZF3/target.h
@@ -71,6 +71,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/CJMCU/hardware_revision.c b/src/main/target/CJMCU/hardware_revision.c
new file mode 100644
index 0000000000..f424ee2aff
--- /dev/null
+++ b/src/main/target/CJMCU/hardware_revision.c
@@ -0,0 +1,53 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "build_config.h"
+
+#include "drivers/system.h"
+#include "drivers/bus_spi.h"
+#include "drivers/sensor.h"
+#include "drivers/accgyro.h"
+#include "drivers/accgyro_spi_mpu6500.h"
+
+#include "hardware_revision.h"
+
+static const char * const hardwareRevisionNames[] = {
+ "Unknown",
+ "R1",
+ "R2"
+};
+
+uint8_t hardwareRevision = UNKNOWN;
+
+void detectHardwareRevision(void)
+{
+ if (GPIOC->IDR & GPIO_Pin_15) {
+ hardwareRevision = REV_2;
+ } else {
+ hardwareRevision = REV_1;
+ }
+}
+
+void updateHardwareRevision(void)
+{
+}
diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h
new file mode 100644
index 0000000000..0b5c255275
--- /dev/null
+++ b/src/main/target/CJMCU/hardware_revision.h
@@ -0,0 +1,27 @@
+/*
+ * 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 .
+ */
+
+typedef enum cjmcuHardwareRevision_t {
+ UNKNOWN = 0,
+ REV_1, // Blue LED3
+ REV_2 // Green LED3
+} cjmcuHardwareRevision_e;
+
+extern uint8_t hardwareRevision;
+
+void updateHardwareRevision(void);
+void detectHardwareRevision(void);
diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h
index 85d5f490c6..2bdabd78e3 100644
--- a/src/main/target/CJMCU/target.h
+++ b/src/main/target/CJMCU/target.h
@@ -18,16 +18,17 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
+#define USE_HARDWARE_REVISION_DETECTION
#define FLASH_PAGE_COUNT 64
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
#define LED0_GPIO GPIOC
-#define LED0_PIN Pin_13 // PC13 (LED)
+#define LED0_PIN Pin_14 // PC14 (LED)
#define LED0
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED1_GPIO GPIOC
-#define LED1_PIN Pin_14 // PC14 (LED)
+#define LED1_PIN Pin_13 // PC13 (LED)
#define LED1
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED2_GPIO GPIOC
diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h
index 682f5c8189..8ef66c2ccc 100644
--- a/src/main/target/EUSTM32F103RC/target.h
+++ b/src/main/target/EUSTM32F103RC/target.h
@@ -104,6 +104,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index 453cb18e9b..1686d523c9 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -18,6 +18,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
+#define USE_HARDWARE_REVISION_DETECTION
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
@@ -124,6 +125,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/NAZE32PRO/target.h b/src/main/target/NAZE32PRO/target.h
index 5376ef9aaa..19f806d71c 100644
--- a/src/main/target/NAZE32PRO/target.h
+++ b/src/main/target/NAZE32PRO/target.h
@@ -43,6 +43,7 @@
#define SENSORS_SET (SENSOR_ACC)
#define GPS
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h
index 6af8a46a3d..0f7805213f 100644
--- a/src/main/target/PORT103R/target.h
+++ b/src/main/target/PORT103R/target.h
@@ -102,6 +102,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
+#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h
index 7df62339de..26cf2f709c 100644
--- a/src/main/target/SPARKY/target.h
+++ b/src/main/target/SPARKY/target.h
@@ -87,10 +87,41 @@
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
+#define BLACKBOX
#define SERIAL_RX
#define GPS
#define DISPLAY
+#define LED_STRIP
+#if 1
+// LED strip configuration using PWM motor output pin 5.
+#define LED_STRIP_TIMER TIM16
+
+#define WS2811_GPIO GPIOA
+#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
+#define WS2811_PIN 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 for some reason the DMA IRQ Transfer Complete is never called.
+#define LED_STRIP_TIMER TIM17
+
+#define WS2811_GPIO GPIOA
+#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
+#define WS2811_PIN 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
// USART2, PA3
#define BIND_PORT GPIOA
diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h
index 18d125635c..561a2f0581 100644
--- a/src/main/target/STM32F3DISCOVERY/target.h
+++ b/src/main/target/STM32F3DISCOVERY/target.h
@@ -56,6 +56,7 @@
#define SENSORS_SET (SENSOR_ACC)
+#define BLACKBOX
#define GPS
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
diff --git a/src/main/version.h b/src/main/version.h
index 1872c1f898..59a5afa312 100644
--- a/src/main/version.h
+++ b/src/main/version.h
@@ -16,7 +16,7 @@
*/
#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
-#define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc)
+#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define MW_VERSION 231