Merge pull request #227 from sherlockflight/master
Add blackbox flight data recorder feature
This commit is contained in:
commit
fcbda7ec63
3
Makefile
3
Makefile
|
@ -219,7 +219,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 \
|
||||
|
|
|
@ -0,0 +1,233 @@
|
|||
# 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/thenickdude/blackbox
|
||||
|
||||
## 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), 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.
|
||||
|
||||
The Blackbox feature is currently available on the Naze32 and Naze32Pro targets. It may work on other targets, but you
|
||||
will need to enable those manually in `/src/main/target/xxx/target.h` by adding a `#define BLACKBOX` statement and
|
||||
recompile Cleanflight.
|
||||
|
||||
## 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 should be flashed with the [OpenLog Lite firmware][] or the special [OpenLog Blackbox variant][] using the Arduino IDE
|
||||
in order to minimise dropped frames (target the "Arduino Uno"). 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.
|
||||
|
||||
If you decide to use the OpenLog Lite firmware instead, note that the .hex file for OpenLog Lite currently in the
|
||||
OpenLog repository is out of date with respect to their .ino source file, so you'll need to build it yourself after
|
||||
adding the [required libraries][] to your Arduino libraries directory.
|
||||
|
||||
To flash the firmware, you'll need to use an FTDI programmer like the [FTDI Basic Breakout][] along with some way of
|
||||
switching the Tx and Rx pins over (since the OpenLog has them switched) like the [FTDI crossover][].
|
||||
|
||||
[OpenLog serial data logger]: https://www.sparkfun.com/products/9530
|
||||
[OpenLog Lite firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light
|
||||
[OpenLog Blackbox variant]: https://github.com/thenickdude/blackbox/tree/blackbox/tools/blackbox/OpenLog_v3_Blackbox
|
||||
[Required libraries]: https://code.google.com/p/beta-lib/downloads/detail?name=SerialLoggerBeta20120108.zip&can=4&q=
|
||||
[FTDI Basic Breakout]: https://www.sparkfun.com/products/9716
|
||||
[FTDI crossover]: https://www.sparkfun.com/products/10660
|
||||
|
||||
### 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.
|
||||
|
||||
### 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 Lite 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, you can [use this one instead][].
|
||||
|
||||
[use this one instead]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/OpenLog_v3_Blackbox/CONFIG.TXT
|
||||
|
||||
### Protection
|
||||
The OpenLog can be wrapped in black electrical tape 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.
|
||||
|
||||

|
||||
|
||||
## Enabling this feature
|
||||
In the [Cleanflight Configurator][], open up the CLI tab. 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
|
||||
```
|
||||
|
||||
## 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 powerup 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.
|
||||
|
||||
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, or render it into a series of
|
||||
PNG frames with `blackbox_render` which you could convert into a video using another software package.
|
||||
|
||||
### Using the blackbox_decode tool
|
||||
This tool converts a flight log binary file into CSV format. Typical usage (from the command line) would be like:
|
||||
|
||||
```bash
|
||||
blackbox_decode LOG00001.TXT
|
||||
```
|
||||
|
||||
That'll decode the log to `LOG00001.01.csv` and print out some statistics about the log. If you're using Windows, you
|
||||
can drag and drop your log files onto `blackbox_decode` and they'll all be decoded.
|
||||
|
||||
Use the `--help` option to show more details:
|
||||
|
||||
```text
|
||||
Blackbox flight log decoder by Nicholas Sherlock
|
||||
|
||||
Usage:
|
||||
blackbox_decode [options] <input logs>
|
||||
|
||||
Options:
|
||||
--help This page
|
||||
--index <num> Choose the log from the file that should be decoded (or omit to decode all)
|
||||
--limits Print the limits and range of each field
|
||||
--stdout Write log to stdout instead of to a file
|
||||
--debug Show extra debugging information
|
||||
--raw Don't apply predictions to fields (show raw field deltas)
|
||||
```
|
||||
|
||||
### Using the blackbox_render tool
|
||||
This tool converts a flight log binary file into a series of transparent PNG images that you could overlay onto your
|
||||
flight video using a video editor (like [DaVinci Resolve][]). Typical usage (from the command line) would be like:
|
||||
|
||||
```bash
|
||||
blackbox_render LOG00001.TXT
|
||||
```
|
||||
|
||||
This will create PNG files at 30 fps into a new directory called `LOG00001.01` next to the log file.
|
||||
|
||||
Use the `--help` option to show more details:
|
||||
|
||||
```text
|
||||
Blackbox flight log renderer by Nicholas Sherlock
|
||||
|
||||
Usage:
|
||||
blackbox_render [options] <logfilename.txt>
|
||||
|
||||
Options:
|
||||
--help This page
|
||||
--index <num> Choose which log from the file should be rendered
|
||||
--width <px> Choose the width of the image (default 1920)
|
||||
--height <px> Choose the height of the image (default 1080)
|
||||
--fps FPS of the resulting video (default 30)
|
||||
--prefix <filename> Set the prefix of the output frame filenames
|
||||
--start <x:xx> Begin the log at this time offset (default 0:00)
|
||||
--end <x:xx> End the log at this time offset
|
||||
--[no-]draw-pid-table Show table with PIDs and gyros (default on)
|
||||
--[no-]draw-craft Show craft drawing (default on)
|
||||
--[no-]draw-sticks Show RC command sticks (default on)
|
||||
--[no-]draw-time Show frame number and time in bottom right (default on)
|
||||
--[no-]plot-motor Draw motors on the upper graph (default on)
|
||||
--[no-]plot-pid Draw PIDs on the lower graph (default off)
|
||||
--[no-]plot-gyro Draw gyroscopes on the lower graph (default on)
|
||||
--smoothing-pid <n> Smoothing window for the PIDs (default 4)
|
||||
--smoothing-gyro <n> Smoothing window for the gyroscopes (default 2)
|
||||
--smoothing-motor <n> Smoothing window for the motors (default 2)
|
||||
--prop-style <name> Style of propeller display (pie/blades, default pie)
|
||||
--gapless Fill in gaps in the log with straight lines
|
||||
```
|
||||
|
||||
(At least on Windows) if you just want to render a log file using the defaults, you can drag and drop a log onto the
|
||||
blackbox_render program and it'll start generating the PNGs immediately.
|
||||
|
||||
[DaVinci Resolve]: https://www.blackmagicdesign.com/products/davinciresolve
|
|
@ -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
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common/axis.h"
|
||||
#include <stdint.h>
|
||||
|
||||
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);
|
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#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;
|
|
@ -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);
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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 };
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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];
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
|
|
@ -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"
|
||||
|
@ -344,6 +345,10 @@ void init(void)
|
|||
initTelemetry();
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
initBlackbox();
|
||||
#endif
|
||||
|
||||
previousTime = micros();
|
||||
|
||||
if (masterConfig.mixerMode == MIXER_GIMBAL) {
|
||||
|
|
|
@ -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;
|
||||
|
@ -698,6 +718,12 @@ void loop(void)
|
|||
mixTable();
|
||||
writeServos();
|
||||
writeMotors();
|
||||
|
||||
#ifdef BLACKBOX
|
||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||
handleBlackbox();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
|
|
@ -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++) {
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -124,6 +124,7 @@
|
|||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
|
@ -43,6 +43,7 @@
|
|||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
Loading…
Reference in New Issue