Merge remote-tracking branch 'upstream/master'
13
Makefile
|
@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
|
||||||
|
|
||||||
FORKNAME = cleanflight
|
FORKNAME = cleanflight
|
||||||
|
|
||||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R
|
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R SPARKY
|
||||||
|
|
||||||
# Valid targets for OP BootLoader support
|
# Valid targets for OP BootLoader support
|
||||||
OPBL_VALID_TARGETS = CC3D
|
OPBL_VALID_TARGETS = CC3D
|
||||||
|
@ -54,7 +54,7 @@ LINKER_DIR = $(ROOT)/src/main/target
|
||||||
# Search path for sources
|
# Search path for sources
|
||||||
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
||||||
|
|
||||||
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO MASSIVEF3))
|
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO MASSIVEF3 SPARKY))
|
||||||
|
|
||||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
||||||
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
|
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
|
||||||
|
@ -267,7 +267,7 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
|
||||||
drivers/bus_i2c_stm32f10x.c \
|
drivers/bus_i2c_stm32f10x.c \
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
drivers/compass_hmc5883l.c \
|
drivers/compass_hmc5883l.c \
|
||||||
drivers/display_ug2864hsweg01.h \
|
drivers/display_ug2864hsweg01.c \
|
||||||
drivers/gpio_stm32f10x.c \
|
drivers/gpio_stm32f10x.c \
|
||||||
drivers/inverter.c \
|
drivers/inverter.c \
|
||||||
drivers/light_led_stm32f10x.c \
|
drivers/light_led_stm32f10x.c \
|
||||||
|
@ -424,6 +424,13 @@ MASSIVEF3_SRC = $(STM32F3DISCOVERY_SRC) \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
|
SPARKY_SRC = $(STM32F30x_COMMON_SRC) \
|
||||||
|
drivers/display_ug2864hsweg01.c \
|
||||||
|
drivers/accgyro_mpu9150.c \
|
||||||
|
drivers/barometer_ms5611.c \
|
||||||
|
$(HIGHEND_SRC) \
|
||||||
|
$(COMMON_SRC)
|
||||||
|
|
||||||
ifeq ($(TARGET),MASSIVEF3)
|
ifeq ($(TARGET),MASSIVEF3)
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
|
||||||
endif
|
endif
|
||||||
|
|
111
README.md
|
@ -1,55 +1,90 @@
|
||||||
# Blackbox flight data recorder port for Cleanflight
|
# Cleanflight
|
||||||
|
|
||||||

|
Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft.
|
||||||
|
|
||||||
WARNING - This firmware is experimental, and may cause your craft to suddenly fall out of the sky. No warranty is
|
This fork differs from baseflight in that it attempts to use modern software development practices which result in:
|
||||||
offered: if your craft breaks, you get to keep both pieces.
|
|
||||||
|
|
||||||
## Introduction
|
1. greater reliability through code robustness and automated testing.
|
||||||
This is a modified version of Cleanflight which adds a flight data recorder function ("Blackbox"). Flight data
|
2. easier maintainance through code cleanliness.
|
||||||
information is transmitted over the flight controller's serial port on every control loop iteration to an external
|
3. easier to develop new features.
|
||||||
logging device to be recorded.
|
4. easier to re-use code though code de-coupling and modularisation.
|
||||||
|
|
||||||
After your flight, you can process the resulting logs on your computer to either turn them into CSV (comma-separated
|
The MultiWii software, from which baseflight originated, violates many good software development best-practices. Hopefully this fork will go some way to address them. If you see any bad code in this fork please immediately raise an issue so it can be fixed, or better yet submit a pull request.
|
||||||
values) or render your flight log as a video.
|
|
||||||
|
|
||||||
This is a port of my Blackbox feature for Baseflight, so please follow the instructions there for usage details (just
|
## Additional Features
|
||||||
use the Cleanflight firmware from this repository instead of the Baseflight firmware):
|
|
||||||
|
|
||||||
https://github.com/thenickdude/blackbox
|
Cleanflight also has additional features not found in baseflight.
|
||||||
|
|
||||||
You will also find the tools to turn your logs into CSV logs or PNG image files. Instructions which are specific to
|
* Multi-color RGB LED Strip support (each LED can be a different color using variable length WS2811 Addressable RGB strips - use for Orientation Indicators, Low Battery Warning, Flight Mode Status, etc)
|
||||||
Cleanflight are included here.
|
* OneShot ESC support.
|
||||||
|
* Support for additional targets that use the STM32F3 processors (baseflight only supports STM32F1).
|
||||||
|
* Support for the TauLabs Sparky board (~$35 STM32F303 I2C sensors, based board with acc/gyro/compass and baro!)
|
||||||
|
* Support for the OpenPilot CC3D board. (~$20 STM32F103 board, SPI acc/gyro)
|
||||||
|
* Support for the CJMCU nano quadcopter board.
|
||||||
|
* Support for developer breakout boards: (Port103R, EUSTM32F103RC, Olimexino, STM32F3Discovery).
|
||||||
|
* Support for more than 8 RC channels - (e.g. 16 Channels via FrSky X4RSB SBus).
|
||||||
|
* Support for N-Position switches via flexible channel ranges - not just 3 like baseflight or 3/6 in MultiWii
|
||||||
|
* Lux's new PID (uses float values internally, resistant to looptime variation).
|
||||||
|
* Simultaneous Bluetooth configuration and OSD.
|
||||||
|
* Better PWM and PPM input and failsafe detection than baseflight.
|
||||||
|
* Better FrSky Telemetry than baseflight.
|
||||||
|
* MSP Telemetry.
|
||||||
|
* RSSI via ADC - Uses ADC to read PWM RSSI signals, tested with FrSky D4R-II and X8R.
|
||||||
|
* Autotune - ported from BradWii, experimental - feedback welcomed.
|
||||||
|
* OLED Displays - Display information on: Battery voltage, profile, rate profile, version, sensors, RC, etc.
|
||||||
|
* In-flight manual PID tuning and rate adjustment.
|
||||||
|
* Rate profiles and in-flight selection of them.
|
||||||
|
* Graupner PPM failsafe.
|
||||||
|
* Graupner HoTT telemetry.
|
||||||
|
* Configurable serial port scenarios for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
|
||||||
|
+ more many minor bug fixes.
|
||||||
|
|
||||||
## Installation of firmware
|
For a list of features, changes and some discussion please review the thread on MultiWii forums and consult the documenation.
|
||||||
Before installing the new firmware onto your Naze32, back up your configuration: Connect to your flight controller
|
|
||||||
using the [Cleanflight Configurator][] , open up the CLI tab and enter "dump" into the box at the bottom and press enter.
|
|
||||||
Copy all of the text that results and paste it into a text document somewhere for safe-keeping.
|
|
||||||
|
|
||||||
Click the disconnect button, then on the main page choose the Firmware Flasher option. Tick the box for "Full Chip
|
http://www.multiwii.com/forum/viewtopic.php?f=23&t=5149
|
||||||
Erase" (warning, this will erase all your settings!). Click the "Load firmware (local)" button, and select the file `cleanflight_NAZE.hex`
|
|
||||||
from the `obj/` directory. Click the "Flash Firmware" button and wait for it to complete.
|
|
||||||
|
|
||||||
Now you need to reload your configuration: Go to the CLI tab and paste in the dump that you saved earlier and press
|
|
||||||
enter, it should execute and restore your settings.
|
|
||||||
|
|
||||||
Before you leave the CLI tab, enable the Blackbox feature by typing in `feature BLACKBOX` and pressing enter. You also
|
## Documentation
|
||||||
need to assign the Blackbox to one of [your serial ports][]. Because it requires a 115200 baud port, the best choice on the
|
|
||||||
Naze32 to use is serial_port_1, which is the two-pin Tx/Rx header in the centre of the board.
|
|
||||||
|
|
||||||
Use `set serial_port_1_scenario=10` to switch the port to Blackbox-only, or `set serial_port_1_scenario=11` to switch it
|
There is lots of documentation here: https://github.com/hydra/cleanflight/tree/master/docs
|
||||||
to MSP, CLI, Blackbox and GPS Passthrough (probably the most useful configuration, since this is the port connected to
|
|
||||||
USB and you'll still want to access the CLI over it).
|
|
||||||
|
|
||||||
Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go!
|
If what you need is not covered then refer to the baseflight documentation. If you still can't find what you need then visit the #cleanflight on the Freenode IRC network
|
||||||
|
|
||||||
If you ever need to disable the Blackbox (say, for example, to switch to using the serial port for an OSD instead), you
|
## IRC Support and Developers Channel
|
||||||
can either reflash the stock firmware using the Configurator, or you can just turn off the Blackbox feature
|
|
||||||
by entering `feature -BLACKBOX` on the CLI tab.
|
|
||||||
|
|
||||||
[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md
|
There's a dedicated IRC channel here:
|
||||||
[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en
|
|
||||||
|
|
||||||
## License
|
irc://irc.freenode.net/#cleanflight
|
||||||
|
|
||||||
This project is licensed under GPLv3.
|
If you are using windows and don't have an IRC client installed then take a look at HydraIRC - here: http://hydrairc.com/
|
||||||
|
|
||||||
|
## Videos
|
||||||
|
|
||||||
|
|
||||||
|
There is a dedicated Cleanflight youtube channel which has progress update videos, flight demonstrations, instrutions and other related videos.
|
||||||
|
|
||||||
|
https://www.youtube.com/playlist?list=PL6H1fAj_XUNVBEcp8vbMH2DrllZAGWkt8
|
||||||
|
|
||||||
|
Please subscribe and '+1' the videos if you find them useful.
|
||||||
|
|
||||||
|
## Configuration Tool
|
||||||
|
|
||||||
|
To configure Cleanflight you should use the Cleanlight-configurator GUI tool (Windows/OSX/Linux) that can be found here:
|
||||||
|
|
||||||
|
https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb
|
||||||
|
|
||||||
|
The source for it is here:
|
||||||
|
|
||||||
|
https://github.com/hydra/cleanflight-configurator
|
||||||
|
|
||||||
|
## Contributing
|
||||||
|
|
||||||
|
Before making any contributions, take a note of the https://github.com/multiwii/baseflight/wiki/CodingStyle
|
||||||
|
|
||||||
|
For this fork it is also advised to read about clean code, here are some useful links:
|
||||||
|
|
||||||
|
* http://cleancoders.com/
|
||||||
|
* http://en.wikipedia.org/wiki/SOLID_%28object-oriented_design%29
|
||||||
|
* http://en.wikipedia.org/wiki/Code_smell
|
||||||
|
* http://en.wikipedia.org/wiki/Code_refactoring
|
||||||
|
* http://www.amazon.co.uk/Working-Effectively-Legacy-Robert-Martin/dp/0131177052
|
||||||
|
|
222
docs/Blackbox.md
Normal file
|
@ -0,0 +1,222 @@
|
||||||
|
# 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
|
||||||
|
as my GPS unit is not functional. 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 me 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 should be flashed with the [OpenLog Lite firmware][] using Arduino IDE in order to minimise dropped frames
|
||||||
|
(target the "Arduino Uno"). Note that the .hex file currently in the OpenLog repository is out of date with respect to
|
||||||
|
the .ino source file, use [this version][] instead. Or you can build your own hex file if you add 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][].
|
||||||
|
|
||||||
|
The original OpenLog firmware may work with acceptable error rates if you use lower data-rates.
|
||||||
|
|
||||||
|
[OpenLog serial data logger]: https://www.sparkfun.com/products/9530
|
||||||
|
[OpenLog Lite firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light
|
||||||
|
[this version][]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/openlog/OpenLog_v3_Light.cpp.hex
|
||||||
|
[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
|
||||||
|
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/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).
|
||||||
|
|
||||||
|
Use `set serial_port_1_scenario=10` to switch the main serial port to Blackbox-only, or `set serial_port_1_scenario=11`
|
||||||
|
to switch it 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.
|
||||||
|
|
||||||
|
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
|
55
docs/Board - Sparky.md
Normal file
|
@ -0,0 +1,55 @@
|
||||||
|
# Board - Sparky
|
||||||
|
|
||||||
|
The Sparky is a very low cost and very powerful board.
|
||||||
|
|
||||||
|
* 3 hardware serial ports.
|
||||||
|
* USB (can be used at the same time as the serial ports).
|
||||||
|
* 10 PWM outputs.
|
||||||
|
* Dedicated PPM/SerialRX input pin.
|
||||||
|
* MPU9150 I2C Acc/Gyro/Mag
|
||||||
|
* Baro
|
||||||
|
|
||||||
|
# Status
|
||||||
|
|
||||||
|
Flyable!
|
||||||
|
|
||||||
|
Tested with revision 1 board.
|
||||||
|
|
||||||
|
## TODO
|
||||||
|
* Mag
|
||||||
|
* Baro
|
||||||
|
* Led Strip
|
||||||
|
* ADC
|
||||||
|
* Display
|
||||||
|
* Softserial - though having 3 hardware serial ports makes it a little redundant.
|
||||||
|
|
||||||
|
# Flashing
|
||||||
|
|
||||||
|
## Via USART1
|
||||||
|
|
||||||
|
Short the bootloader pads and flash using configurator or the st flashloader tool via USART1.
|
||||||
|
Unshort bootloader pads after flashing.
|
||||||
|
|
||||||
|
## Via SWD
|
||||||
|
|
||||||
|
On the bottom of the board there is an SWD header socket onto switch a JST-SH connector can be soldered.
|
||||||
|
Once you have SWD connected you can use the st-link or j-link tools to flash a binary.
|
||||||
|
|
||||||
|
See Sparky schematic for CONN2 pinouts.
|
||||||
|
|
||||||
|
## TauLabs bootloader
|
||||||
|
|
||||||
|
Flashing cleanflight will erase the TauLabs bootloader, this is not a problem and can easily be restored using the st flashloader tool.
|
||||||
|
|
||||||
|
# Serial Ports
|
||||||
|
|
||||||
|
| Value | Identifier | RX | TX | Notes |
|
||||||
|
| ----- | ------------ | --------- | ---------- | ------------------------------------------------------------------------------------------- |
|
||||||
|
| 1 | USB VCP | RX (USB) | TX (USB) | |
|
||||||
|
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port |
|
||||||
|
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input. |
|
||||||
|
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
|
||||||
|
|
||||||
|
USB VCP *can* be used at the same time as other serial ports (unlike Naze32).
|
||||||
|
|
||||||
|
|
|
@ -67,6 +67,6 @@ More can be read about this procedure here: http://www.multiwii.com/forum/viewto
|
||||||
|
|
||||||
Connect +5v, Ground, I2C SDA and I2C SCL from the flight controller to the display.
|
Connect +5v, Ground, I2C SDA and I2C SCL from the flight controller to the display.
|
||||||
|
|
||||||
On Naze32 rev 5 boards the SDA and SCL pins are underneath the board.
|
On Naze32 rev 5 boards the SDA and SCL pads are underneath the board.
|
||||||
|
|
||||||
|
|
||||||
|
|
100
docs/Gps.md
|
@ -12,9 +12,12 @@ Enable the GPS from the CLI as follows:
|
||||||
4) connect your GPS to a serial port that supports GPS and set an approprate `serial_port_x_scenario` to `2`. where `x` is a serial port number.
|
4) connect your GPS to a serial port that supports GPS and set an approprate `serial_port_x_scenario` to `2`. where `x` is a serial port number.
|
||||||
5) `save`.
|
5) `save`.
|
||||||
|
|
||||||
For the last step check the Board documentation for pins and port numbers and check the Serial documentation for details on serial port scenarios where you will also find some example configurations.
|
Note: GPS packet loss has been observed at 115200. Try using 57600 if you experience this.
|
||||||
|
|
||||||
## GPS Provider
|
For the connections step check the Board documentation for pins and port numbers and check the Serial documentation for details on serial port scenarios where you will also find some example configurations.
|
||||||
|
|
||||||
|
|
||||||
|
### GPS Provider
|
||||||
|
|
||||||
Set the `gps_provider` appropriately.
|
Set the `gps_provider` appropriately.
|
||||||
|
|
||||||
|
@ -23,7 +26,15 @@ Set the `gps_provider` appropriately.
|
||||||
| 0 | NMEA |
|
| 0 | NMEA |
|
||||||
| 1 | UBLOX |
|
| 1 | UBLOX |
|
||||||
|
|
||||||
## SBAS
|
### GPS Auto configuration
|
||||||
|
|
||||||
|
When using UBLOX it is a good idea to use GPS auto configuration so your FC gets the GPS messages it needs.
|
||||||
|
|
||||||
|
Enable GPS auto configuration as follows `set gps_auto_config=1`.
|
||||||
|
|
||||||
|
If you are not using GPS auto configuration then ensure your GPS receiver sends out the correct messages at the right frequency. See below for manual UBlox settings.
|
||||||
|
|
||||||
|
### SBAS
|
||||||
|
|
||||||
When using a UBLOX GPS the SBAS mode can be configured using `gps_sbas_mode`.
|
When using a UBLOX GPS the SBAS mode can be configured using `gps_sbas_mode`.
|
||||||
|
|
||||||
|
@ -38,3 +49,86 @@ The default is AUTO.
|
||||||
| 4 | GAGAN | India |
|
| 4 | GAGAN | India |
|
||||||
|
|
||||||
If you use a regional specific setting you may achieve a faster GPS lock than using AUTO.
|
If you use a regional specific setting you may achieve a faster GPS lock than using AUTO.
|
||||||
|
|
||||||
|
This setting only works when `gps_auto_config=1`
|
||||||
|
|
||||||
|
## GPS Receiver Configuration
|
||||||
|
|
||||||
|
UBlox GPS units can either be configured using the FC or manually.
|
||||||
|
|
||||||
|
### UBlox GPS manual configuration
|
||||||
|
|
||||||
|
Use UBox U-Center and connect your GPS to your computer. The cli `gpspassthough` command may be of use if you do not have a spare USART to USB adapter.
|
||||||
|
|
||||||
|
Display the Packet Console (so you can see what messages your receiver is sending to your computer).
|
||||||
|
|
||||||
|
Display the Configation View.
|
||||||
|
|
||||||
|
Navigate to CFG (Configuration)
|
||||||
|
|
||||||
|
Select `Revert to default configuration`.
|
||||||
|
Click `Send`.
|
||||||
|
|
||||||
|
At this point you might need to disconnect and reconnect at the default baudrate - probably 9600 baud.
|
||||||
|
|
||||||
|
Navigate to PRT (Ports)
|
||||||
|
|
||||||
|
Set `Target` to `1 - Uart 1`
|
||||||
|
Set `Protocol In` to `0+1+2`
|
||||||
|
Set `Protocol Out` to `0+1`
|
||||||
|
Set `Buadrate` to `57600` `115200`
|
||||||
|
Press `Send`
|
||||||
|
|
||||||
|
This will immediatly "break" communication to the GPS. Since you haven't saved the new baudrate setting to the non-volatile memory you need to change the baudrate you communicate to the GPS without resetting the GPS. So `Disconnect`, Change baud rate to match, then `Connect`.
|
||||||
|
|
||||||
|
Click on `PRT` in the Configuration view again and inspect the packet console to make sure messages are being sent and acknowledged.
|
||||||
|
|
||||||
|
Next, to ensure the FC doesn't waste time processing messages it does not need you must disable all messages on except:
|
||||||
|
|
||||||
|
NAV-POSLLH
|
||||||
|
NAV-DOP
|
||||||
|
NAV-SOL
|
||||||
|
NAV-VELNED
|
||||||
|
NAV-TIMEUTC
|
||||||
|
|
||||||
|
The above messages should each be enabled with a rate of `1`.
|
||||||
|
|
||||||
|
NAV-SVINFO
|
||||||
|
|
||||||
|
The above messages should each be enabled with a rate of `5` to reduce bandwidth and load on the FC.
|
||||||
|
|
||||||
|
When changing message target and rates remember to click `Send` after changing each message.
|
||||||
|
|
||||||
|
Next change the global update rate, click `Rate (Rates)` in the Configuration view.
|
||||||
|
|
||||||
|
Set `Measurement period` to `100` ms.
|
||||||
|
Set `Navigation rate` to `1`.
|
||||||
|
Click `Send`.
|
||||||
|
|
||||||
|
This will cause the GPS receive to send the require messages out 10 times a second. If your GPS receiver cannot be set to use `100`ms try `200`ms (5hz) - this is less precise.
|
||||||
|
|
||||||
|
Next change the mode, click `NAV5 (Navigation 5)` in the Configuration View.
|
||||||
|
|
||||||
|
Set to `Dynamic Model` to `Pedestrian` and click `Send`.
|
||||||
|
|
||||||
|
Next change the SBAS settings. Click `SBAS (SBAS Settings)` in the Configuration View.
|
||||||
|
|
||||||
|
Set `Subsystem` to `Enabled`.
|
||||||
|
Set `PRN Codes` to `Auto-Scan`.
|
||||||
|
Click `Send`.
|
||||||
|
|
||||||
|
Finally, we need to save the configuration.
|
||||||
|
|
||||||
|
Click `CFG (Configuration` in the Configuration View.
|
||||||
|
|
||||||
|
Select `Save current configuration` and click `Send`.
|
||||||
|
|
||||||
|
### UBlox Navigation model
|
||||||
|
|
||||||
|
Cleanflight will use `Pedestrian` when gps auto config is used.
|
||||||
|
|
||||||
|
From the UBlox documentation:
|
||||||
|
|
||||||
|
* Pedestrian - Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical, Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small.
|
||||||
|
* Portable - Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium.
|
||||||
|
* Airborne < 1G - Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
|
||||||
|
|
|
@ -88,7 +88,7 @@ The Range Channel and the Adjustment Channel can be the same channel. This is u
|
||||||
to a single adjustment function regardless of other switch positions.
|
to a single adjustment function regardless of other switch positions.
|
||||||
|
|
||||||
The adjustment functions is applied to the adjustment channel when range channel between the range values.
|
The adjustment functions is applied to the adjustment channel when range channel between the range values.
|
||||||
The adjustment is made when the adjustment channel is in the high or low position. high = midrc + 200, low = midrc - 200. by default this is 1700 and 1500 respectively.
|
The adjustment is made when the adjustment channel is in the high or low position. high = midrc + 200, low = midrc - 200. by default this is 1700 and 1300 respectively.
|
||||||
|
|
||||||
### Adjustment function
|
### Adjustment function
|
||||||
|
|
||||||
|
|
|
@ -1,144 +1,99 @@
|
||||||
# Building in windows
|
# Building in windows
|
||||||
|
|
||||||
1- Install cygwin, and GNU Tools ARM Embedded (make sure make is installed).
|
|
||||||
cygwin: https://cygwin.com/install.html
|
|
||||||
gnu tools arm embedded: https://launchpad.net/gcc-arm-embedded
|
|
||||||
|
|
||||||
2- In a terminal go to cleanflight directory
|
##Setup Cygwin
|
||||||
|
|
||||||
3- make clean
|
download the Setup*.exe from https://www.cygwin.com/
|
||||||
|
|
||||||
4- rm -rf obj
|

|
||||||
|
|
||||||
5- make
|
Execute the download Setup and step through the installation wizard (no need to customize the settings here). Stop at the "Select Packages" Screen and select the following Packages
|
||||||
|
for Installation:
|
||||||
|
|
||||||
This should work.Something like this output should be the result:
|
- Devel/git
|
||||||
C:\Users\nico\Documents\GitHub\cleanflight>make
|
- Devel/git-completion (Optional)
|
||||||
%% startup_stm32f10x_md_gcc.s
|
- Devel/make
|
||||||
%% accgyro_adxl345.c
|
- Devel/binutils
|
||||||
%% accgyro_bma280.c
|
- Editors/vim
|
||||||
%% accgyro_l3g4200d.c
|
- Editors/vim-common (Optional)
|
||||||
%% accgyro_mma845x.c
|
- Shells/mintty (should be already selected)
|
||||||
%% accgyro_mpu3050.c
|
|
||||||
%% accgyro_mpu6050.c
|
|
||||||
%% adc_common.c
|
|
||||||
%% adc_stm32f10x.c
|
|
||||||
%% barometer_bmp085.c
|
|
||||||
%% barometer_ms5611.c
|
|
||||||
%% bus_spi.c
|
|
||||||
%% bus_i2c_stm32f10x.c
|
|
||||||
%% compass_hmc5883l.c
|
|
||||||
%% gpio_stm32f10x.c
|
|
||||||
%% light_ledring.c
|
|
||||||
%% sonar_hcsr04.c
|
|
||||||
%% pwm_mapping.c
|
|
||||||
%% pwm_output.c
|
|
||||||
%% pwm_rssi.c
|
|
||||||
%% pwm_rx.c
|
|
||||||
%% serial_softserial.c
|
|
||||||
%% serial_uart_common.c
|
|
||||||
%% serial_uart_stm32f10x.c
|
|
||||||
%% timer_common.c
|
|
||||||
%% build_config.c
|
|
||||||
%% battery.c
|
|
||||||
%% boardalignment.c
|
|
||||||
%% beeper.c
|
|
||||||
%% config.c
|
|
||||||
%% maths.c
|
|
||||||
%% printf.c
|
|
||||||
%% typeconversion.c
|
|
||||||
%% failsafe.c
|
|
||||||
%% main.c
|
|
||||||
%% mw.c
|
|
||||||
%% sensors_acceleration.c
|
|
||||||
%% sensors_barometer.c
|
|
||||||
%% sensors_compass.c
|
|
||||||
%% sensors_gyro.c
|
|
||||||
%% sensors_initialisation.c
|
|
||||||
%% sensors_sonar.c
|
|
||||||
%% bus_i2c_soft.c
|
|
||||||
%% serial_common.c
|
|
||||||
%% sound_beeper.c
|
|
||||||
%% system_common.c
|
|
||||||
%% flight_common.c
|
|
||||||
%% flight_imu.c
|
|
||||||
%% flight_mixer.c
|
|
||||||
%% gps_common.c
|
|
||||||
%% runtime_config.c
|
|
||||||
%% rc_controls.c
|
|
||||||
%% rc_curves.c
|
|
||||||
%% rx_common.c
|
|
||||||
%% rx_msp.c
|
|
||||||
%% rx_pwm.c
|
|
||||||
%% rx_sbus.c
|
|
||||||
%% rx_sumd.c
|
|
||||||
%% rx_spektrum.c
|
|
||||||
%% telemetry_common.c
|
|
||||||
%% telemetry_frsky.c
|
|
||||||
%% telemetry_hott.c
|
|
||||||
%% serial_common.c
|
|
||||||
%% serial_cli.c
|
|
||||||
%% serial_msp.c
|
|
||||||
%% statusindicator.c
|
|
||||||
%% core_cm3.c
|
|
||||||
%% system_stm32f10x.c
|
|
||||||
%% stm32f10x_gpio.c
|
|
||||||
%% stm32f10x_fsmc.c
|
|
||||||
%% stm32f10x_exti.c
|
|
||||||
%% stm32f10x_bkp.c
|
|
||||||
%% stm32f10x_spi.c
|
|
||||||
%% stm32f10x_adc.c
|
|
||||||
%% stm32f10x_iwdg.c
|
|
||||||
%% misc.c
|
|
||||||
%% stm32f10x_cec.c
|
|
||||||
%% stm32f10x_wwdg.c
|
|
||||||
%% stm32f10x_tim.c
|
|
||||||
%% stm32f10x_usart.c
|
|
||||||
%% stm32f10x_crc.c
|
|
||||||
%% stm32f10x_flash.c
|
|
||||||
%% stm32f10x_rcc.c
|
|
||||||
%% stm32f10x_sdio.c
|
|
||||||
%% stm32f10x_i2c.c
|
|
||||||
%% stm32f10x_pwr.c
|
|
||||||
%% stm32f10x_rtc.c
|
|
||||||
%% stm32f10x_can.c
|
|
||||||
%% stm32f10x_dac.c
|
|
||||||
%% stm32f10x_dbgmcu.c
|
|
||||||
%% stm32f10x_dma.c
|
|
||||||
arm-none-eabi-gcc -o obj/cleanflight_NAZE.elf obj/NAZE/startup_stm32f10x_md_gcc.
|
|
||||||
o obj/NAZE/drivers/accgyro_adxl345.o obj/NAZE/drivers/accgyro_bma280.o obj/NAZE/
|
|
||||||
drivers/accgyro_l3g4200d.o obj/NAZE/drivers/accgyro_mma845x.o obj/NAZE/drivers/a
|
|
||||||
ccgyro_mpu3050.o obj/NAZE/drivers/accgyro_mpu6050.o obj/NAZE/drivers/adc_common.
|
|
||||||
o obj/NAZE/drivers/adc_stm32f10x.o obj/NAZE/drivers/barometer_bmp085.o obj/NAZE/
|
|
||||||
drivers/barometer_ms5611.o obj/NAZE/drivers/bus_spi.o obj/NAZE/drivers/bus_i2c_s
|
|
||||||
tm32f10x.o obj/NAZE/drivers/compass_hmc5883l.o obj/NAZE/drivers/gpio_stm32f10x.o
|
|
||||||
obj/NAZE/drivers/light_ledring.o obj/NAZE/drivers/sonar_hcsr04.o obj/NAZE/drive
|
|
||||||
rs/pwm_mapping.o obj/NAZE/drivers/pwm_output.o obj/NAZE/drivers/pwm_rssi.o obj/N
|
|
||||||
AZE/drivers/pwm_rx.o obj/NAZE/drivers/serial_softserial.o obj/NAZE/drivers/seria
|
|
||||||
l_uart_common.o obj/NAZE/drivers/serial_uart_stm32f10x.o obj/NAZE/drivers/timer_
|
|
||||||
common.o obj/NAZE/build_config.o obj/NAZE/battery.o obj/NAZE/boardalignment.o ob
|
|
||||||
j/NAZE/beeper.o obj/NAZE/config.o obj/NAZE/common/maths.o obj/NAZE/common/printf
|
|
||||||
.o obj/NAZE/common/typeconversion.o obj/NAZE/failsafe.o obj/NAZE/main.o obj/NAZE
|
|
||||||
/mw.o obj/NAZE/sensors_acceleration.o obj/NAZE/sensors_barometer.o obj/NAZE/sens
|
|
||||||
ors_compass.o obj/NAZE/sensors_gyro.o obj/NAZE/sensors_initialisation.o obj/NAZE
|
|
||||||
/sensors_sonar.o obj/NAZE/drivers/bus_i2c_soft.o obj/NAZE/drivers/serial_common.
|
|
||||||
o obj/NAZE/drivers/sound_beeper.o obj/NAZE/drivers/system_common.o obj/NAZE/flig
|
|
||||||
ht_common.o obj/NAZE/flight_imu.o obj/NAZE/flight_mixer.o obj/NAZE/gps_common.o
|
|
||||||
obj/NAZE/runtime_config.o obj/NAZE/rc_controls.o obj/NAZE/rc_curves.o obj/NAZE/r
|
|
||||||
x_common.o obj/NAZE/rx_msp.o obj/NAZE/rx_pwm.o obj/NAZE/rx_sbus.o obj/NAZE/rx_su
|
|
||||||
md.o obj/NAZE/rx_spektrum.o obj/NAZE/telemetry_common.o obj/NAZE/telemetry_frsky
|
|
||||||
.o obj/NAZE/telemetry_hott.o obj/NAZE/serial_common.o obj/NAZE/serial_cli.o obj/
|
|
||||||
NAZE/serial_msp.o obj/NAZE/statusindicator.o obj/NAZE/core_cm3.o obj/NAZE/system
|
|
||||||
_stm32f10x.o obj/NAZE/stm32f10x_gpio.o obj/NAZE/stm32f10x_fsmc.o obj/NAZE/stm32f
|
|
||||||
10x_exti.o obj/NAZE/stm32f10x_bkp.o obj/NAZE/stm32f10x_spi.o obj/NAZE/stm32f10x_
|
|
||||||
adc.o obj/NAZE/stm32f10x_iwdg.o obj/NAZE/misc.o obj/NAZE/stm32f10x_cec.o obj/NAZ
|
|
||||||
E/stm32f10x_wwdg.o obj/NAZE/stm32f10x_tim.o obj/NAZE/stm32f10x_usart.o obj/NAZE/
|
|
||||||
stm32f10x_crc.o obj/NAZE/stm32f10x_flash.o obj/NAZE/stm32f10x_rcc.o obj/NAZE/stm
|
|
||||||
32f10x_sdio.o obj/NAZE/stm32f10x_i2c.o obj/NAZE/stm32f10x_pwr.o obj/NAZE/stm32f1
|
|
||||||
0x_rtc.o obj/NAZE/stm32f10x_can.o obj/NAZE/stm32f10x_dac.o obj/NAZE/stm32f10x_db
|
|
||||||
gmcu.o obj/NAZE/stm32f10x_dma.o -lm -mthumb -mcpu=cortex-m3 -static -Wl,-gc-sect
|
|
||||||
ions,-Map,.//obj/cleanflight_NAZE.map -T.//stm32_flash_f103.ld
|
|
||||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/cleanflight_NAZE.elf obj
|
|
||||||
/cleanflight_NAZE.hex
|
|
||||||
|
|
||||||
cleanflight_NAZE.hex is about 220kb.
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
|
||||||
|
Continue with the Installation and accept all autodetected dependencies.
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
|
||||||
|
##Setup GNU ARM Toolchain
|
||||||
|
|
||||||
|
----------
|
||||||
|
|
||||||
|
versions do matter, 4.8-2014-q2 is known to work well. Download this version from htps://launchpad.net/gcc-arm-embedded/+download - preferrebly as a ZIP-File.
|
||||||
|
|
||||||
|
|
||||||
|
Extract the contents of this archive to any folder of your choice, for instance ```C:\dev\gcc-arm-none-eabi-4_8-2014q2```.
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
add the "bin" subdirectory to the PATH Windows environment variable: ```%PATH%;C:\dev\gcc-arm-none-eabi-4_8-2014q2\bin```
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
## Checkout and compile Cleanflight
|
||||||
|
|
||||||
|
Head over to the Cleanflight Github page and grab the URL of the GIT Repository: "https://github.com/cleanflight/cleanflight.git"
|
||||||
|
|
||||||
|
Open the Cygwin-Terminal, navigate to your development folder and use the git commandline to checkout the repository:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
cd /cygdrive/c/dev
|
||||||
|
git clone https://github.com/cleanflight/cleanflight.git
|
||||||
|
```
|
||||||
|

|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
To compile your Cleanflight binaries, enter the cleanflight directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default NAZE target:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
cd cleanflight
|
||||||
|
make TARGET=NAZE
|
||||||
|
```
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
within few moments you should have your binary ready:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
(...)
|
||||||
|
arm-none-eabi-size ./obj/main/cleanflight_NAZE.elf
|
||||||
|
text data bss dec hex filename
|
||||||
|
95388 308 10980 106676 1a0b4 ./obj/main/cleanflight_NAZE.elf
|
||||||
|
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/cleanflight_NAZE.elf obj/cleanflight_NAZE.hex
|
||||||
|
```
|
||||||
|
|
||||||
|
You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file.
|
||||||
|
|
||||||
|
## Updating and rebuilding
|
||||||
|
|
||||||
|
Navigate to the local cleanflight repository and use the following steps to pull the latest changes and rebuild your version of cleanflight:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
cd /cygdrive/c/dev/cleanflight
|
||||||
|
git reset --hard
|
||||||
|
git pull
|
||||||
|
make clean TARGET=NAZE
|
||||||
|
make
|
||||||
|
```
|
||||||
|
|
BIN
docs/development/assets/001.cygwin_dl.png
Executable file
After Width: | Height: | Size: 121 KiB |
BIN
docs/development/assets/002.cygwin_setup.png
Executable file
After Width: | Height: | Size: 31 KiB |
BIN
docs/development/assets/003.cygwin_setup.png
Executable file
After Width: | Height: | Size: 50 KiB |
BIN
docs/development/assets/004.cygwin_setup.png
Executable file
After Width: | Height: | Size: 25 KiB |
BIN
docs/development/assets/005.cygwin_setup.png
Executable file
After Width: | Height: | Size: 22 KiB |
BIN
docs/development/assets/006.cygwin_setup.png
Executable file
After Width: | Height: | Size: 19 KiB |
BIN
docs/development/assets/007.cygwin_setup.png
Executable file
After Width: | Height: | Size: 15 KiB |
BIN
docs/development/assets/008.toolchain.png
Executable file
After Width: | Height: | Size: 31 KiB |
BIN
docs/development/assets/009.toolchain_path.png
Executable file
After Width: | Height: | Size: 33 KiB |
BIN
docs/development/assets/010.toolchain_path.png
Executable file
After Width: | Height: | Size: 146 KiB |
BIN
docs/development/assets/011.git_checkout.png
Executable file
After Width: | Height: | Size: 86 KiB |
BIN
docs/development/assets/012.git_checkout.png
Executable file
After Width: | Height: | Size: 21 KiB |
BIN
docs/development/assets/013.compile.png
Executable file
After Width: | Height: | Size: 21 KiB |
BIN
obj/cleanflight_CC3D.bin
Executable file
5035
obj/cleanflight_CC3D.hex
Normal file
3929
obj/cleanflight_CJMCU.hex
Normal file
11981
obj/cleanflight_NAZE.hex
4977
obj/cleanflight_SPARKY.hex
Normal file
|
@ -37,6 +37,8 @@
|
||||||
|
|
||||||
extern int16_t debug[4];
|
extern int16_t debug[4];
|
||||||
|
|
||||||
|
#define DEBUG_SECTION_TIMES
|
||||||
|
|
||||||
#ifdef DEBUG_SECTION_TIMES
|
#ifdef DEBUG_SECTION_TIMES
|
||||||
extern uint32_t sectionTimes[2][4];
|
extern uint32_t sectionTimes[2][4];
|
||||||
|
|
||||||
|
|
|
@ -104,7 +104,7 @@ profile_t *currentProfile;
|
||||||
static uint8_t currentControlRateProfileIndex = 0;
|
static uint8_t currentControlRateProfileIndex = 0;
|
||||||
controlRateConfig_t *currentControlRateProfile;
|
controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 85;
|
static const uint8_t EEPROM_CONF_VERSION = 86;
|
||||||
|
|
||||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
{
|
{
|
||||||
|
@ -127,15 +127,15 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
pidProfile->P8[PIDALT] = 50;
|
pidProfile->P8[PIDALT] = 50;
|
||||||
pidProfile->I8[PIDALT] = 0;
|
pidProfile->I8[PIDALT] = 0;
|
||||||
pidProfile->D8[PIDALT] = 0;
|
pidProfile->D8[PIDALT] = 0;
|
||||||
pidProfile->P8[PIDPOS] = 11; // POSHOLD_P * 100;
|
pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
|
||||||
pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
|
pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
|
||||||
pidProfile->D8[PIDPOS] = 0;
|
pidProfile->D8[PIDPOS] = 0;
|
||||||
pidProfile->P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10;
|
pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
|
||||||
pidProfile->I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100;
|
pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
|
||||||
pidProfile->D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000;
|
pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
|
||||||
pidProfile->P8[PIDNAVR] = 14; // NAV_P * 10;
|
pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
|
||||||
pidProfile->I8[PIDNAVR] = 20; // NAV_I * 100;
|
pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
|
||||||
pidProfile->D8[PIDNAVR] = 80; // NAV_D * 1000;
|
pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
|
||||||
pidProfile->P8[PIDLEVEL] = 90;
|
pidProfile->P8[PIDLEVEL] = 90;
|
||||||
pidProfile->I8[PIDLEVEL] = 10;
|
pidProfile->I8[PIDLEVEL] = 10;
|
||||||
pidProfile->D8[PIDLEVEL] = 100;
|
pidProfile->D8[PIDLEVEL] = 100;
|
||||||
|
@ -306,7 +306,7 @@ static void resetConf(void)
|
||||||
masterConfig.version = EEPROM_CONF_VERSION;
|
masterConfig.version = EEPROM_CONF_VERSION;
|
||||||
masterConfig.mixerConfiguration = MULTITYPE_QUADX;
|
masterConfig.mixerConfiguration = MULTITYPE_QUADX;
|
||||||
featureClearAll();
|
featureClearAll();
|
||||||
#ifdef CJMCU
|
#if defined(CJMCU) || defined(SPARKY)
|
||||||
featureSet(FEATURE_RX_PPM);
|
featureSet(FEATURE_RX_PPM);
|
||||||
#endif
|
#endif
|
||||||
featureSet(FEATURE_VBAT);
|
featureSet(FEATURE_VBAT);
|
||||||
|
@ -334,6 +334,7 @@ static void resetConf(void)
|
||||||
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
||||||
|
|
||||||
masterConfig.rxConfig.serialrx_provider = 0;
|
masterConfig.rxConfig.serialrx_provider = 0;
|
||||||
|
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
||||||
masterConfig.rxConfig.midrc = 1500;
|
masterConfig.rxConfig.midrc = 1500;
|
||||||
masterConfig.rxConfig.mincheck = 1100;
|
masterConfig.rxConfig.mincheck = 1100;
|
||||||
masterConfig.rxConfig.maxcheck = 1900;
|
masterConfig.rxConfig.maxcheck = 1900;
|
||||||
|
@ -364,7 +365,8 @@ static void resetConf(void)
|
||||||
// gps/nav stuff
|
// gps/nav stuff
|
||||||
masterConfig.gpsConfig.provider = GPS_NMEA;
|
masterConfig.gpsConfig.provider = GPS_NMEA;
|
||||||
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
||||||
masterConfig.gpsConfig.gpsAutoConfig = GPS_AUTOCONFIG_ON;
|
masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||||
|
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
resetSerialConfig(&masterConfig.serialConfig);
|
resetSerialConfig(&masterConfig.serialConfig);
|
||||||
|
|
|
@ -27,8 +27,8 @@ typedef enum {
|
||||||
extern uint8_t armingFlags;
|
extern uint8_t armingFlags;
|
||||||
|
|
||||||
#define DISABLE_ARMING_FLAG(mask) (armingFlags &= ~(mask))
|
#define DISABLE_ARMING_FLAG(mask) (armingFlags &= ~(mask))
|
||||||
#define ENABLE_ARMING_FLAG(mask) (armingFlags |= mask)
|
#define ENABLE_ARMING_FLAG(mask) (armingFlags |= (mask))
|
||||||
#define ARMING_FLAG(mask) (armingFlags & mask)
|
#define ARMING_FLAG(mask) (armingFlags & (mask))
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ANGLE_MODE = (1 << 0),
|
ANGLE_MODE = (1 << 0),
|
||||||
|
@ -46,8 +46,8 @@ typedef enum {
|
||||||
extern uint16_t flightModeFlags;
|
extern uint16_t flightModeFlags;
|
||||||
|
|
||||||
#define DISABLE_FLIGHT_MODE(mask) (flightModeFlags &= ~(mask))
|
#define DISABLE_FLIGHT_MODE(mask) (flightModeFlags &= ~(mask))
|
||||||
#define ENABLE_FLIGHT_MODE(mask) (flightModeFlags |= mask)
|
#define ENABLE_FLIGHT_MODE(mask) (flightModeFlags |= (mask))
|
||||||
#define FLIGHT_MODE(mask) (flightModeFlags & mask)
|
#define FLIGHT_MODE(mask) (flightModeFlags & (mask))
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_FIX_HOME = (1 << 0),
|
GPS_FIX_HOME = (1 << 0),
|
||||||
|
@ -58,8 +58,8 @@ typedef enum {
|
||||||
} stateFlags_t;
|
} stateFlags_t;
|
||||||
|
|
||||||
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))
|
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))
|
||||||
#define ENABLE_STATE(mask) (stateFlags |= mask)
|
#define ENABLE_STATE(mask) (stateFlags |= (mask))
|
||||||
#define STATE(mask) (stateFlags & mask)
|
#define STATE(mask) (stateFlags & (mask))
|
||||||
|
|
||||||
extern uint8_t stateFlags;
|
extern uint8_t stateFlags;
|
||||||
|
|
||||||
|
|
|
@ -307,7 +307,10 @@ static void mpu6050AccRead(int16_t *accData)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
||||||
i2cRead(MPU6050_ADDRESS, MPU_RA_ACCEL_XOUT_H, 6, buf);
|
if (!i2cRead(MPU6050_ADDRESS, MPU_RA_ACCEL_XOUT_H, 6, buf)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
accData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
accData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||||
accData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
accData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||||
accData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
accData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||||
|
@ -338,7 +341,9 @@ static void mpu6050GyroRead(int16_t *gyroData)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
||||||
i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf);
|
if (!i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||||
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||||
|
|
353
src/main/drivers/accgyro_mpu9150.c
Normal file
|
@ -0,0 +1,353 @@
|
||||||
|
/*
|
||||||
|
* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// NOTE: this file is a copy of the mpu6050 driver with very minimal changes.
|
||||||
|
// some de-duplication needs to occur...
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
#include "system.h"
|
||||||
|
#include "gpio.h"
|
||||||
|
#include "bus_i2c.h"
|
||||||
|
|
||||||
|
#include "accgyro.h"
|
||||||
|
#include "accgyro_mpu9150.h"
|
||||||
|
|
||||||
|
#define MPU9150_ADDRESS 0xD0
|
||||||
|
|
||||||
|
#define DMP_MEM_START_ADDR 0x6E
|
||||||
|
#define DMP_MEM_R_W 0x6F
|
||||||
|
|
||||||
|
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
|
||||||
|
#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
|
||||||
|
#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
|
||||||
|
#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
|
||||||
|
#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
|
||||||
|
#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
|
||||||
|
#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
|
||||||
|
#define MPU_RA_XA_OFFS_L_TC 0x07
|
||||||
|
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
|
||||||
|
#define MPU_RA_YA_OFFS_L_TC 0x09
|
||||||
|
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
|
||||||
|
#define MPU_RA_ZA_OFFS_L_TC 0x0B
|
||||||
|
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
|
||||||
|
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
|
||||||
|
#define MPU_RA_XG_OFFS_USRL 0x14
|
||||||
|
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
|
||||||
|
#define MPU_RA_YG_OFFS_USRL 0x16
|
||||||
|
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
|
||||||
|
#define MPU_RA_ZG_OFFS_USRL 0x18
|
||||||
|
#define MPU_RA_SMPLRT_DIV 0x19
|
||||||
|
#define MPU_RA_CONFIG 0x1A
|
||||||
|
#define MPU_RA_GYRO_CONFIG 0x1B
|
||||||
|
#define MPU_RA_ACCEL_CONFIG 0x1C
|
||||||
|
#define MPU_RA_FF_THR 0x1D
|
||||||
|
#define MPU_RA_FF_DUR 0x1E
|
||||||
|
#define MPU_RA_MOT_THR 0x1F
|
||||||
|
#define MPU_RA_MOT_DUR 0x20
|
||||||
|
#define MPU_RA_ZRMOT_THR 0x21
|
||||||
|
#define MPU_RA_ZRMOT_DUR 0x22
|
||||||
|
#define MPU_RA_FIFO_EN 0x23
|
||||||
|
#define MPU_RA_I2C_MST_CTRL 0x24
|
||||||
|
#define MPU_RA_I2C_SLV0_ADDR 0x25
|
||||||
|
#define MPU_RA_I2C_SLV0_REG 0x26
|
||||||
|
#define MPU_RA_I2C_SLV0_CTRL 0x27
|
||||||
|
#define MPU_RA_I2C_SLV1_ADDR 0x28
|
||||||
|
#define MPU_RA_I2C_SLV1_REG 0x29
|
||||||
|
#define MPU_RA_I2C_SLV1_CTRL 0x2A
|
||||||
|
#define MPU_RA_I2C_SLV2_ADDR 0x2B
|
||||||
|
#define MPU_RA_I2C_SLV2_REG 0x2C
|
||||||
|
#define MPU_RA_I2C_SLV2_CTRL 0x2D
|
||||||
|
#define MPU_RA_I2C_SLV3_ADDR 0x2E
|
||||||
|
#define MPU_RA_I2C_SLV3_REG 0x2F
|
||||||
|
#define MPU_RA_I2C_SLV3_CTRL 0x30
|
||||||
|
#define MPU_RA_I2C_SLV4_ADDR 0x31
|
||||||
|
#define MPU_RA_I2C_SLV4_REG 0x32
|
||||||
|
#define MPU_RA_I2C_SLV4_DO 0x33
|
||||||
|
#define MPU_RA_I2C_SLV4_CTRL 0x34
|
||||||
|
#define MPU_RA_I2C_SLV4_DI 0x35
|
||||||
|
#define MPU_RA_I2C_MST_STATUS 0x36
|
||||||
|
#define MPU_RA_INT_PIN_CFG 0x37
|
||||||
|
#define MPU_RA_INT_ENABLE 0x38
|
||||||
|
#define MPU_RA_DMP_INT_STATUS 0x39
|
||||||
|
#define MPU_RA_INT_STATUS 0x3A
|
||||||
|
#define MPU_RA_ACCEL_XOUT_H 0x3B
|
||||||
|
#define MPU_RA_ACCEL_XOUT_L 0x3C
|
||||||
|
#define MPU_RA_ACCEL_YOUT_H 0x3D
|
||||||
|
#define MPU_RA_ACCEL_YOUT_L 0x3E
|
||||||
|
#define MPU_RA_ACCEL_ZOUT_H 0x3F
|
||||||
|
#define MPU_RA_ACCEL_ZOUT_L 0x40
|
||||||
|
#define MPU_RA_TEMP_OUT_H 0x41
|
||||||
|
#define MPU_RA_TEMP_OUT_L 0x42
|
||||||
|
#define MPU_RA_GYRO_XOUT_H 0x43
|
||||||
|
#define MPU_RA_GYRO_XOUT_L 0x44
|
||||||
|
#define MPU_RA_GYRO_YOUT_H 0x45
|
||||||
|
#define MPU_RA_GYRO_YOUT_L 0x46
|
||||||
|
#define MPU_RA_GYRO_ZOUT_H 0x47
|
||||||
|
#define MPU_RA_GYRO_ZOUT_L 0x48
|
||||||
|
#define MPU_RA_EXT_SENS_DATA_00 0x49
|
||||||
|
#define MPU_RA_MOT_DETECT_STATUS 0x61
|
||||||
|
#define MPU_RA_I2C_SLV0_DO 0x63
|
||||||
|
#define MPU_RA_I2C_SLV1_DO 0x64
|
||||||
|
#define MPU_RA_I2C_SLV2_DO 0x65
|
||||||
|
#define MPU_RA_I2C_SLV3_DO 0x66
|
||||||
|
#define MPU_RA_I2C_MST_DELAY_CTRL 0x67
|
||||||
|
#define MPU_RA_SIGNAL_PATH_RESET 0x68
|
||||||
|
#define MPU_RA_MOT_DETECT_CTRL 0x69
|
||||||
|
#define MPU_RA_USER_CTRL 0x6A
|
||||||
|
#define MPU_RA_PWR_MGMT_1 0x6B
|
||||||
|
#define MPU_RA_PWR_MGMT_2 0x6C
|
||||||
|
#define MPU_RA_BANK_SEL 0x6D
|
||||||
|
#define MPU_RA_MEM_START_ADDR 0x6E
|
||||||
|
#define MPU_RA_MEM_R_W 0x6F
|
||||||
|
#define MPU_RA_DMP_CFG_1 0x70
|
||||||
|
#define MPU_RA_DMP_CFG_2 0x71
|
||||||
|
#define MPU_RA_FIFO_COUNTH 0x72
|
||||||
|
#define MPU_RA_FIFO_COUNTL 0x73
|
||||||
|
#define MPU_RA_FIFO_R_W 0x74
|
||||||
|
#define MPU_RA_WHO_AM_I 0x75
|
||||||
|
|
||||||
|
#define MPU9150_SMPLRT_DIV 0 // 8000Hz
|
||||||
|
|
||||||
|
enum lpf_e {
|
||||||
|
INV_FILTER_256HZ_NOLPF2 = 0,
|
||||||
|
INV_FILTER_188HZ,
|
||||||
|
INV_FILTER_98HZ,
|
||||||
|
INV_FILTER_42HZ,
|
||||||
|
INV_FILTER_20HZ,
|
||||||
|
INV_FILTER_10HZ,
|
||||||
|
INV_FILTER_5HZ,
|
||||||
|
INV_FILTER_2100HZ_NOLPF,
|
||||||
|
NUM_FILTER
|
||||||
|
};
|
||||||
|
enum gyro_fsr_e {
|
||||||
|
INV_FSR_250DPS = 0,
|
||||||
|
INV_FSR_500DPS,
|
||||||
|
INV_FSR_1000DPS,
|
||||||
|
INV_FSR_2000DPS,
|
||||||
|
NUM_GYRO_FSR
|
||||||
|
};
|
||||||
|
enum clock_sel_e {
|
||||||
|
INV_CLK_INTERNAL = 0,
|
||||||
|
INV_CLK_PLL,
|
||||||
|
NUM_CLK
|
||||||
|
};
|
||||||
|
enum accel_fsr_e {
|
||||||
|
INV_FSR_2G = 0,
|
||||||
|
INV_FSR_4G,
|
||||||
|
INV_FSR_8G,
|
||||||
|
INV_FSR_16G,
|
||||||
|
NUM_ACCEL_FSR
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint8_t mpuLowPassFilter = INV_FILTER_42HZ;
|
||||||
|
static void mpu9150AccInit(void);
|
||||||
|
static void mpu9150AccRead(int16_t *accData);
|
||||||
|
static void mpu9150GyroInit(void);
|
||||||
|
static void mpu9150GyroRead(int16_t *gyroData);
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MPU_9150_HALF_RESOLUTION,
|
||||||
|
MPU_9150_FULL_RESOLUTION
|
||||||
|
} mpu9150Resolution_e;
|
||||||
|
|
||||||
|
static mpu9150Resolution_e mpuAccelTrim;
|
||||||
|
|
||||||
|
static const mpu9150Config_t *mpu9150Config = NULL;
|
||||||
|
|
||||||
|
void mpu9150GpioInit(void) {
|
||||||
|
gpio_config_t gpio;
|
||||||
|
|
||||||
|
if (mpu9150Config->gpioAPB2Peripherals) {
|
||||||
|
RCC_APB2PeriphClockCmd(mpu9150Config->gpioAPB2Peripherals, ENABLE);
|
||||||
|
}
|
||||||
|
|
||||||
|
gpio.pin = mpu9150Config->gpioPin;
|
||||||
|
gpio.speed = Speed_2MHz;
|
||||||
|
gpio.mode = Mode_IN_FLOATING;
|
||||||
|
gpioInit(mpu9150Config->gpioPort, &gpio);
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool mpu9150Detect(void)
|
||||||
|
{
|
||||||
|
bool ack;
|
||||||
|
uint8_t sig;
|
||||||
|
|
||||||
|
ack = i2cRead(MPU9150_ADDRESS, MPU_RA_WHO_AM_I, 1, &sig);
|
||||||
|
if (!ack) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// So like, MPU6xxx has a "WHO_AM_I" register, that is used to verify the identity of the device.
|
||||||
|
// The contents of WHO_AM_I are the upper 6 bits of the MPU-60X0<58>s 7-bit I2C address.
|
||||||
|
// The least significant bit of the MPU-60X0<58>s I2C address is determined by the value of the AD0 pin. (we know that already).
|
||||||
|
// But here's the best part: The value of the AD0 pin is not reflected in this register.
|
||||||
|
|
||||||
|
return true;
|
||||||
|
|
||||||
|
if (sig != (MPU9150_ADDRESS & 0x7e))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool mpu9150AccDetect(const mpu9150Config_t *configToUse, acc_t *acc)
|
||||||
|
{
|
||||||
|
uint8_t readBuffer[6];
|
||||||
|
uint8_t revision;
|
||||||
|
uint8_t productId;
|
||||||
|
|
||||||
|
mpu9150Config = configToUse;
|
||||||
|
|
||||||
|
if (!mpu9150Detect()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// There is a map of revision contained in the android source tree which is quite comprehensive and may help to understand this code
|
||||||
|
// See https://android.googlesource.com/kernel/msm.git/+/eaf36994a3992b8f918c18e4f7411e8b2320a35f/drivers/misc/mpu6050/mldl_cfg.c
|
||||||
|
|
||||||
|
// determine product ID and accel revision
|
||||||
|
i2cRead(MPU9150_ADDRESS, MPU_RA_XA_OFFS_H, 6, readBuffer);
|
||||||
|
revision = ((readBuffer[5] & 0x01) << 2) | ((readBuffer[3] & 0x01) << 1) | (readBuffer[1] & 0x01);
|
||||||
|
if (revision) {
|
||||||
|
/* Congrats, these parts are better. */
|
||||||
|
if (revision == 1) {
|
||||||
|
mpuAccelTrim = MPU_9150_HALF_RESOLUTION;
|
||||||
|
} else if (revision == 2) {
|
||||||
|
mpuAccelTrim = MPU_9150_FULL_RESOLUTION;
|
||||||
|
} else {
|
||||||
|
failureMode(5);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
i2cRead(MPU9150_ADDRESS, MPU_RA_PRODUCT_ID, 1, &productId);
|
||||||
|
revision = productId & 0x0F;
|
||||||
|
if (!revision) {
|
||||||
|
failureMode(5);
|
||||||
|
} else if (revision == 4) {
|
||||||
|
mpuAccelTrim = MPU_9150_HALF_RESOLUTION;
|
||||||
|
} else {
|
||||||
|
mpuAccelTrim = MPU_9150_FULL_RESOLUTION;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
acc->init = mpu9150AccInit;
|
||||||
|
acc->read = mpu9150AccRead;
|
||||||
|
acc->revisionCode = (mpuAccelTrim == MPU_9150_HALF_RESOLUTION ? 'o' : 'n');
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool mpu9150GyroDetect(const mpu9150Config_t *configToUse, gyro_t *gyro, uint16_t lpf)
|
||||||
|
{
|
||||||
|
mpu9150Config = configToUse;
|
||||||
|
|
||||||
|
if (!mpu9150Detect()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
gyro->init = mpu9150GyroInit;
|
||||||
|
gyro->read = mpu9150GyroRead;
|
||||||
|
|
||||||
|
// 16.4 dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
if (lpf >= 188)
|
||||||
|
mpuLowPassFilter = INV_FILTER_188HZ;
|
||||||
|
else if (lpf >= 98)
|
||||||
|
mpuLowPassFilter = INV_FILTER_98HZ;
|
||||||
|
else if (lpf >= 42)
|
||||||
|
mpuLowPassFilter = INV_FILTER_42HZ;
|
||||||
|
else if (lpf >= 20)
|
||||||
|
mpuLowPassFilter = INV_FILTER_20HZ;
|
||||||
|
else if (lpf >= 10)
|
||||||
|
mpuLowPassFilter = INV_FILTER_10HZ;
|
||||||
|
else
|
||||||
|
mpuLowPassFilter = INV_FILTER_5HZ;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void mpu9150AccInit(void)
|
||||||
|
{
|
||||||
|
if (mpu9150Config) {
|
||||||
|
mpu9150GpioInit();
|
||||||
|
mpu9150Config = NULL; // avoid re-initialisation of GPIO;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (mpuAccelTrim) {
|
||||||
|
case MPU_9150_HALF_RESOLUTION:
|
||||||
|
acc_1G = 256 * 8;
|
||||||
|
break;
|
||||||
|
case MPU_9150_FULL_RESOLUTION:
|
||||||
|
acc_1G = 512 * 8;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void mpu9150AccRead(int16_t *accData)
|
||||||
|
{
|
||||||
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
if (!i2cRead(MPU9150_ADDRESS, MPU_RA_ACCEL_XOUT_H, 6, buf)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
accData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||||
|
accData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||||
|
accData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void mpu9150GyroInit(void)
|
||||||
|
{
|
||||||
|
if (mpu9150Config) {
|
||||||
|
mpu9150GpioInit();
|
||||||
|
mpu9150Config = NULL; // avoid re-initialisation of GPIO;
|
||||||
|
}
|
||||||
|
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||||
|
delay(100);
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_SMPLRT_DIV, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_INT_PIN_CFG,
|
||||||
|
0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_CONFIG, mpuLowPassFilter); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
|
||||||
|
|
||||||
|
// ACC Init stuff. Moved into gyro init because the reset above would screw up accel config. Oops.
|
||||||
|
// Accel scale 8g (4096 LSB/g)
|
||||||
|
i2cWrite(MPU9150_ADDRESS, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void mpu9150GyroRead(int16_t *gyroData)
|
||||||
|
{
|
||||||
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
if (!i2cRead(MPU9150_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||||
|
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||||
|
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||||
|
}
|
29
src/main/drivers/accgyro_mpu9150.h
Normal file
|
@ -0,0 +1,29 @@
|
||||||
|
/*
|
||||||
|
* 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 struct mpu9150Config_s {
|
||||||
|
uint32_t gpioAPB2Peripherals;
|
||||||
|
uint16_t gpioPin;
|
||||||
|
GPIO_TypeDef *gpioPort;
|
||||||
|
} mpu9150Config_t;
|
||||||
|
|
||||||
|
bool mpu9150AccDetect(const mpu9150Config_t *config,acc_t *acc);
|
||||||
|
bool mpu9150GyroDetect(const mpu9150Config_t *config, gyro_t *gyro, uint16_t lpf);
|
||||||
|
void mpu9150DmpLoop(void);
|
||||||
|
void mpu9150DmpResetFifo(void);
|
|
@ -69,11 +69,11 @@ void adcInit(drv_adc_config_t *init)
|
||||||
if (init->enableRSSI) {
|
if (init->enableRSSI) {
|
||||||
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_2;
|
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_2;
|
||||||
|
|
||||||
adcConfig[ADC_RSSI].adcChannel = ADC_Channel_8;
|
adcConfig[ADC_RSSI].adcChannel = ADC_Channel_8;
|
||||||
adcConfig[ADC_RSSI].dmaIndex = adcChannelCount;
|
adcConfig[ADC_RSSI].dmaIndex = adcChannelCount;
|
||||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5;
|
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5;
|
||||||
adcConfig[ADC_RSSI].enabled = true;
|
adcConfig[ADC_RSSI].enabled = true;
|
||||||
adcChannelCount++;
|
adcChannelCount++;
|
||||||
}
|
}
|
||||||
|
|
||||||
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_9;
|
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_9;
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
@ -33,28 +34,37 @@
|
||||||
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
||||||
|
|
||||||
#define I2C1_SCL_GPIO GPIOB
|
#define I2C1_SCL_GPIO GPIOB
|
||||||
|
#define I2C1_SCL_GPIO_AF GPIO_AF_4
|
||||||
#define I2C1_SCL_PIN GPIO_Pin_6
|
#define I2C1_SCL_PIN GPIO_Pin_6
|
||||||
#define I2C1_SCL_PIN_SOURCE GPIO_PinSource6
|
#define I2C1_SCL_PIN_SOURCE GPIO_PinSource6
|
||||||
#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
||||||
#define I2C1_SDA_GPIO GPIOB
|
#define I2C1_SDA_GPIO GPIOB
|
||||||
|
#define I2C1_SDA_GPIO_AF GPIO_AF_4
|
||||||
#define I2C1_SDA_PIN GPIO_Pin_7
|
#define I2C1_SDA_PIN GPIO_Pin_7
|
||||||
#define I2C1_SDA_PIN_SOURCE GPIO_PinSource7
|
#define I2C1_SDA_PIN_SOURCE GPIO_PinSource7
|
||||||
#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
||||||
|
|
||||||
|
#if !defined(I2C2_SCL_GPIO)
|
||||||
#define I2C2_SCL_GPIO GPIOF
|
#define I2C2_SCL_GPIO GPIOF
|
||||||
|
#define I2C2_SCL_GPIO_AF GPIO_AF_4
|
||||||
#define I2C2_SCL_PIN GPIO_Pin_6
|
#define I2C2_SCL_PIN GPIO_Pin_6
|
||||||
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource6
|
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource6
|
||||||
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOF
|
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOF
|
||||||
#define I2C2_SDA_GPIO GPIOA
|
#define I2C2_SDA_GPIO GPIOA
|
||||||
|
#define I2C2_SDA_GPIO_AF GPIO_AF_4
|
||||||
#define I2C2_SDA_PIN GPIO_Pin_10
|
#define I2C2_SDA_PIN GPIO_Pin_10
|
||||||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
static uint32_t i2cTimeout;
|
static uint32_t i2cTimeout;
|
||||||
|
|
||||||
static volatile uint16_t i2c1ErrorCount = 0;
|
static volatile uint16_t i2c1ErrorCount = 0;
|
||||||
static volatile uint16_t i2c2ErrorCount = 0;
|
static volatile uint16_t i2c2ErrorCount = 0;
|
||||||
|
|
||||||
|
static I2C_TypeDef *I2Cx = NULL;
|
||||||
|
|
||||||
///////////////////////////////////////////////////////////////////////////////
|
///////////////////////////////////////////////////////////////////////////////
|
||||||
// I2C TimeoutUserCallback
|
// I2C TimeoutUserCallback
|
||||||
///////////////////////////////////////////////////////////////////////////////
|
///////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -75,15 +85,14 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||||
I2C_InitTypeDef I2C_InitStructure;
|
I2C_InitTypeDef I2C_InitStructure;
|
||||||
|
|
||||||
if (I2Cx == I2C1) {
|
if (I2Cx == I2C1) {
|
||||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
|
||||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
|
|
||||||
RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE);
|
RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE);
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
|
||||||
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
|
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
|
||||||
|
|
||||||
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
||||||
|
|
||||||
GPIO_PinAFConfig(I2C1_SCL_GPIO, I2C1_SCL_PIN_SOURCE, GPIO_AF_4);
|
GPIO_PinAFConfig(I2C1_SCL_GPIO, I2C1_SCL_PIN_SOURCE, I2C1_SCL_GPIO_AF);
|
||||||
GPIO_PinAFConfig(I2C1_SDA_GPIO, I2C1_SDA_PIN_SOURCE, GPIO_AF_4);
|
GPIO_PinAFConfig(I2C1_SDA_GPIO, I2C1_SDA_PIN_SOURCE, I2C1_SDA_GPIO_AF);
|
||||||
|
|
||||||
GPIO_StructInit(&GPIO_InitStructure);
|
GPIO_StructInit(&GPIO_InitStructure);
|
||||||
I2C_StructInit(&I2C_InitStructure);
|
I2C_StructInit(&I2C_InitStructure);
|
||||||
|
@ -118,15 +127,14 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (I2Cx == I2C2) {
|
if (I2Cx == I2C2) {
|
||||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
|
||||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
|
||||||
RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE);
|
RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE);
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
||||||
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
|
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
|
||||||
|
|
||||||
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
||||||
|
|
||||||
GPIO_PinAFConfig(I2C2_SCL_GPIO, I2C2_SCL_PIN_SOURCE, GPIO_AF_4);
|
GPIO_PinAFConfig(I2C2_SCL_GPIO, I2C2_SCL_PIN_SOURCE, I2C2_SCL_GPIO_AF);
|
||||||
GPIO_PinAFConfig(I2C2_SDA_GPIO, I2C2_SDA_PIN_SOURCE, GPIO_AF_4);
|
GPIO_PinAFConfig(I2C2_SDA_GPIO, I2C2_SDA_PIN_SOURCE, I2C2_SDA_GPIO_AF);
|
||||||
|
|
||||||
GPIO_StructInit(&GPIO_InitStructure);
|
GPIO_StructInit(&GPIO_InitStructure);
|
||||||
I2C_StructInit(&I2C_InitStructure);
|
I2C_StructInit(&I2C_InitStructure);
|
||||||
|
@ -134,7 +142,7 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||||
// Init pins
|
// Init pins
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||||
|
|
||||||
GPIO_InitStructure.GPIO_Pin = I2C2_SCL_PIN;
|
GPIO_InitStructure.GPIO_Pin = I2C2_SCL_PIN;
|
||||||
|
@ -151,7 +159,14 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||||
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
|
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
|
||||||
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||||
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||||
|
|
||||||
|
// FIXME timing is board specific
|
||||||
|
//I2C_InitStructure.I2C_Timing = 0x00310309; // //400kHz I2C @ 8MHz input -> PRESC=0x0, SCLDEL=0x3, SDADEL=0x1, SCLH=0x03, SCLL=0x09 - value from TauLabs/Sparky
|
||||||
|
// ^ when using this setting and after a few seconds of a scope probe being attached to the I2C bus it was observed that the bus enters
|
||||||
|
// a busy state and does not recover.
|
||||||
|
|
||||||
I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||||
|
|
||||||
//I2C_InitStructure.I2C_Timing = 0x8000050B;
|
//I2C_InitStructure.I2C_Timing = 0x8000050B;
|
||||||
|
|
||||||
I2C_Init(I2C2, &I2C_InitStructure);
|
I2C_Init(I2C2, &I2C_InitStructure);
|
||||||
|
@ -162,19 +177,26 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||||
|
|
||||||
void i2cInit(I2CDevice index)
|
void i2cInit(I2CDevice index)
|
||||||
{
|
{
|
||||||
UNUSED(index);
|
if (index == I2CDEV_1) {
|
||||||
i2cInitPort(I2C1); // FIXME hard coded to use I2C1 for now
|
I2Cx = I2C1;
|
||||||
|
} else {
|
||||||
|
I2Cx = I2C2;
|
||||||
|
}
|
||||||
|
i2cInitPort(I2Cx);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t i2cGetErrorCounter(void)
|
uint16_t i2cGetErrorCounter(void)
|
||||||
{
|
{
|
||||||
return i2c1ErrorCount;
|
if (I2Cx == I2C1) {
|
||||||
|
return i2c1ErrorCount;
|
||||||
|
}
|
||||||
|
|
||||||
|
return i2c2ErrorCount;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
|
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
|
||||||
{
|
{
|
||||||
I2C_TypeDef* I2Cx = I2C1;
|
|
||||||
|
|
||||||
/* Test on BUSY Flag */
|
/* Test on BUSY Flag */
|
||||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||||
|
@ -236,7 +258,6 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
|
||||||
|
|
||||||
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||||
{
|
{
|
||||||
I2C_TypeDef* I2Cx = I2C1;
|
|
||||||
/* Test on BUSY Flag */
|
/* Test on BUSY Flag */
|
||||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||||
|
|
|
@ -153,12 +153,19 @@ static const uint8_t const multiWiiFont[][5] = { // Refer to "Times New Roman" F
|
||||||
{ 0x17, 0x08, 0x34, 0x2A, 0x7D }, // (119) /4 - 0x00BC Vulgar Fraction One Quarter
|
{ 0x17, 0x08, 0x34, 0x2A, 0x7D }, // (119) /4 - 0x00BC Vulgar Fraction One Quarter
|
||||||
{ 0x17, 0x08, 0x04, 0x6A, 0x59 }, // (120) /2 - 0x00BD Vulgar Fraction One Half
|
{ 0x17, 0x08, 0x04, 0x6A, 0x59 }, // (120) /2 - 0x00BD Vulgar Fraction One Half
|
||||||
{ 0x30, 0x48, 0x45, 0x40, 0x20 }, // (121) ? - 0x00BE Inverted Question Mark
|
{ 0x30, 0x48, 0x45, 0x40, 0x20 }, // (121) ? - 0x00BE Inverted Question Mark
|
||||||
{ 0x42, 0x00, 0x42, 0x00, 0x42 }, // (122) - 0x00BF Bargraph - 0
|
{ 0x42, 0x00, 0x42, 0x00, 0x42 }, // (122) - 0x00BF Horizontal Bargraph - 0 (empty)
|
||||||
{ 0x7E, 0x42, 0x00, 0x42, 0x00 }, // (123) - 0x00BF Bargraph - 1
|
{ 0x7E, 0x42, 0x00, 0x42, 0x00 }, // (123) - 0x00C0 Horizontal Bargraph - 1
|
||||||
{ 0x7E, 0x7E, 0x00, 0x42, 0x00 }, // (124) - 0x00BF Bargraph - 2
|
{ 0x7E, 0x7E, 0x00, 0x42, 0x00 }, // (124) - 0x00C1 Horizontal Bargraph - 2
|
||||||
{ 0x7E, 0x7E, 0x7E, 0x42, 0x00 }, // (125) - 0x00BF Bargraph - 3
|
{ 0x7E, 0x7E, 0x7E, 0x42, 0x00 }, // (125) - 0x00C2 Horizontal Bargraph - 3
|
||||||
{ 0x7E, 0x7E, 0x7E, 0x7E, 0x00 }, // (126) - 0x00BF Bargraph - 4
|
{ 0x7E, 0x7E, 0x7E, 0x7E, 0x00 }, // (126) - 0x00C3 Horizontal Bargraph - 4
|
||||||
{ 0x7E, 0x7E, 0x7E, 0x7E, 0x7E }, // (127) - 0x00BF Bargraph - 5
|
{ 0x7E, 0x7E, 0x7E, 0x7E, 0x7E }, // (127) - 0x00C4 Horizontal Bargraph - 5 (full)
|
||||||
|
{ 0x5A, 0x00, 0x00, 0x00, 0x5A }, // (128) - 0x00C5 Vertical Bargraph - 0 (empty)
|
||||||
|
{ 0x5A, 0x40, 0x40, 0x40, 0x5A }, // (129) - 0x00C6 Vertical Bargraph - 1
|
||||||
|
{ 0x7A, 0x60, 0x60, 0x60, 0x7A }, // (130) - 0x00C7 Vertical Bargraph - 2
|
||||||
|
{ 0x7A, 0x70, 0x70, 0x70, 0x7A }, // (131) - 0x00C8 Vertical Bargraph - 3
|
||||||
|
{ 0x7A, 0x78, 0x78, 0x78, 0x7A }, // (131) - 0x00C8 Vertical Bargraph - 4
|
||||||
|
{ 0x7A, 0x7C, 0x7C, 0x7C, 0x7A }, // (131) - 0x00C8 Vertical Bargraph - 5
|
||||||
|
{ 0x7A, 0x7E, 0x7E, 0x7E, 0x7A }, // (131) - 0x00C8 Vertical Bargraph - 6 (full)
|
||||||
};
|
};
|
||||||
|
|
||||||
#define OLED_address 0x3C // OLED at address 0x3C in 7bit
|
#define OLED_address 0x3C // OLED at address 0x3C in 7bit
|
||||||
|
|
|
@ -31,6 +31,9 @@
|
||||||
#define SCREEN_CHARACTER_COLUMN_COUNT (SCREEN_WIDTH / CHARACTER_WIDTH_TOTAL)
|
#define SCREEN_CHARACTER_COLUMN_COUNT (SCREEN_WIDTH / CHARACTER_WIDTH_TOTAL)
|
||||||
#define SCREEN_CHARACTER_ROW_COUNT (SCREEN_HEIGHT / CHARACTER_HEIGHT_TOTAL)
|
#define SCREEN_CHARACTER_ROW_COUNT (SCREEN_HEIGHT / CHARACTER_HEIGHT_TOTAL)
|
||||||
|
|
||||||
|
#define VERTICAL_BARGRAPH_ZERO_CHARACTER (128 + 32)
|
||||||
|
#define VERTICAL_BARGRAPH_CHARACTER_COUNT 7
|
||||||
|
|
||||||
void ug2864hsweg01InitI2C(void);
|
void ug2864hsweg01InitI2C(void);
|
||||||
|
|
||||||
void i2c_OLED_set_xy(uint8_t col, uint8_t row);
|
void i2c_OLED_set_xy(uint8_t col, uint8_t row);
|
||||||
|
|
|
@ -47,7 +47,7 @@ void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
|
||||||
if (config->pin & pinMask) {
|
if (config->pin & pinMask) {
|
||||||
|
|
||||||
GPIO_InitStructure.GPIO_Pin = pinMask;
|
GPIO_InitStructure.GPIO_Pin = pinMask;
|
||||||
GPIO_InitStructure.GPIO_Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
|
GPIO_InitStructure.GPIO_Mode = (config->mode & MODE_MASK) >> MODE_OFFSET;
|
||||||
|
|
||||||
GPIOSpeed_TypeDef speed = GPIO_Speed_10MHz;
|
GPIOSpeed_TypeDef speed = GPIO_Speed_10MHz;
|
||||||
switch (config->speed) {
|
switch (config->speed) {
|
||||||
|
@ -63,8 +63,8 @@ void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
|
||||||
}
|
}
|
||||||
|
|
||||||
GPIO_InitStructure.GPIO_Speed = speed;
|
GPIO_InitStructure.GPIO_Speed = speed;
|
||||||
GPIO_InitStructure.GPIO_OType = (config->mode >> OUTPUT_OFFSET) & OUTPUT_MASK;
|
GPIO_InitStructure.GPIO_OType = (config->mode & OUTPUT_MASK) >> OUTPUT_OFFSET;
|
||||||
GPIO_InitStructure.GPIO_PuPd = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
|
GPIO_InitStructure.GPIO_PuPd = (config->mode & PUPD_MASK) >> PUPD_OFFSET;
|
||||||
GPIO_Init(gpio, &GPIO_InitStructure);
|
GPIO_Init(gpio, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,6 +14,8 @@
|
||||||
#define NVIC_PRIO_SERIALUART2_TXDMA NVIC_BUILD_PRIORITY(1, 0)
|
#define NVIC_PRIO_SERIALUART2_TXDMA NVIC_BUILD_PRIORITY(1, 0)
|
||||||
#define NVIC_PRIO_SERIALUART2_RXDMA NVIC_BUILD_PRIORITY(1, 1)
|
#define NVIC_PRIO_SERIALUART2_RXDMA NVIC_BUILD_PRIORITY(1, 1)
|
||||||
#define NVIC_PRIO_SERIALUART2 NVIC_BUILD_PRIORITY(1, 2)
|
#define NVIC_PRIO_SERIALUART2 NVIC_BUILD_PRIORITY(1, 2)
|
||||||
|
#define NVIC_PRIO_SERIALUART3_TXDMA NVIC_BUILD_PRIORITY(1, 0)
|
||||||
|
#define NVIC_PRIO_SERIALUART3_RXDMA NVIC_BUILD_PRIORITY(1, 1)
|
||||||
#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2)
|
#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2)
|
||||||
#define NVIC_PRIO_I2C_ER NVIC_BUILD_PRIORITY(0, 0)
|
#define NVIC_PRIO_I2C_ER NVIC_BUILD_PRIORITY(0, 0)
|
||||||
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
|
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
|
||||||
|
|
|
@ -233,6 +233,46 @@ static const uint16_t airPPM[] = {
|
||||||
static const uint16_t airPWM[] = {
|
static const uint16_t airPWM[] = {
|
||||||
0xFFFF
|
0xFFFF
|
||||||
};
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef SPARKY
|
||||||
|
static const uint16_t multiPPM[] = {
|
||||||
|
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||||
|
|
||||||
|
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15
|
||||||
|
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15
|
||||||
|
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1
|
||||||
|
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||||
|
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||||
|
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2
|
||||||
|
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||||
|
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17
|
||||||
|
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||||
|
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t multiPWM[] = {
|
||||||
|
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t airPPM[] = {
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t airPWM[] = {
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -322,19 +362,25 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
|
|
||||||
// hacks to allow current functionality
|
// hacks to allow current functionality
|
||||||
if (type == MAP_TO_PWM_INPUT && !init->useParallelPWM)
|
if (type == MAP_TO_PWM_INPUT && !init->useParallelPWM)
|
||||||
type = 0;
|
continue;
|
||||||
|
|
||||||
if (type == MAP_TO_PPM_INPUT && !init->usePPM)
|
if (type == MAP_TO_PPM_INPUT && !init->usePPM)
|
||||||
type = 0;
|
continue;
|
||||||
|
|
||||||
if (init->useServos && !init->airplane) {
|
if (init->useServos && !init->airplane) {
|
||||||
#if defined(STM32F10X) || defined(CHEBUZZF3)
|
#if defined(NAZE)
|
||||||
// remap PWM9+10 as servos
|
// remap PWM9+10 as servos
|
||||||
if (timerIndex == PWM9 || timerIndex == PWM10)
|
if ((timerIndex == PWM9 || timerIndex == PWM10) && timerHardwarePtr->tim == TIM1)
|
||||||
type = MAP_TO_SERVO_OUTPUT;
|
type = MAP_TO_SERVO_OUTPUT;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if (defined(STM32F303xC) || defined(STM32F3DISCOVERY)) && !defined(CHEBUZZF3)
|
#if defined(SPARKY)
|
||||||
|
// remap PWM1+2 as servos
|
||||||
|
if ((timerIndex == PWM1 || timerIndex == PWM2) && timerHardwarePtr->tim == TIM15)
|
||||||
|
type = MAP_TO_SERVO_OUTPUT;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(NAZE32PRO) || (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3))
|
||||||
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
|
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
|
||||||
if (init->useSoftSerial) {
|
if (init->useSoftSerial) {
|
||||||
if (timerIndex == PWM5 || timerIndex == PWM6)
|
if (timerIndex == PWM5 || timerIndex == PWM6)
|
||||||
|
@ -354,6 +400,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
if (init->useParallelPWM) {
|
if (init->useParallelPWM) {
|
||||||
|
// Skip PWM inputs that conflict with timers used outputs.
|
||||||
if ((type == MAP_TO_SERVO_OUTPUT || type == MAP_TO_MOTOR_OUTPUT) && (timerHardwarePtr->tim == TIM2 || timerHardwarePtr->tim == TIM3)) {
|
if ((type == MAP_TO_SERVO_OUTPUT || type == MAP_TO_MOTOR_OUTPUT) && (timerHardwarePtr->tim == TIM2 || timerHardwarePtr->tim == TIM3)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
|
@ -97,6 +97,8 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
||||||
|
|
||||||
configTimeBase(timerHardware->tim, period, mhz);
|
configTimeBase(timerHardware->tim, period, mhz);
|
||||||
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
|
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
|
||||||
|
|
||||||
|
|
||||||
pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
|
pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
|
||||||
if (timerHardware->outputEnable)
|
if (timerHardware->outputEnable)
|
||||||
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
|
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
|
||||||
|
|
|
@ -205,10 +205,19 @@ void uartStartTxDMA(uartPort_t *s)
|
||||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
uartPort_t *s = (uartPort_t*)instance;
|
uartPort_t *s = (uartPort_t*)instance;
|
||||||
if (s->rxDMAChannel)
|
if (s->rxDMAChannel) {
|
||||||
return (s->rxDMAChannel->CNDTR - s->rxDMAPos) & (s->port.txBufferSize - 1);
|
uint32_t rxDMAHead = s->rxDMAChannel->CNDTR;
|
||||||
else {
|
if (rxDMAHead >= s->rxDMAPos) {
|
||||||
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.txBufferSize - 1);
|
return rxDMAHead - s->rxDMAPos;
|
||||||
|
} else {
|
||||||
|
return s->port.rxBufferSize + rxDMAHead - s->rxDMAPos;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s->port.rxBufferHead >= s->port.rxBufferTail) {
|
||||||
|
return s->port.rxBufferHead - s->port.rxBufferTail;
|
||||||
|
} else {
|
||||||
|
return s->port.rxBufferSize + s->port.rxBufferHead - s->port.rxBufferTail;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -232,7 +241,11 @@ uint8_t uartRead(serialPort_t *instance)
|
||||||
s->rxDMAPos = s->port.rxBufferSize;
|
s->rxDMAPos = s->port.rxBufferSize;
|
||||||
} else {
|
} else {
|
||||||
ch = s->port.rxBuffer[s->port.rxBufferTail];
|
ch = s->port.rxBuffer[s->port.rxBufferTail];
|
||||||
s->port.rxBufferTail = (s->port.rxBufferTail + 1) % s->port.rxBufferSize;
|
if (s->port.rxBufferTail + 1 >= s->port.rxBufferSize) {
|
||||||
|
s->port.rxBufferTail = 0;
|
||||||
|
} else {
|
||||||
|
s->port.rxBufferTail++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return ch;
|
return ch;
|
||||||
|
@ -242,7 +255,11 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
|
||||||
{
|
{
|
||||||
uartPort_t *s = (uartPort_t *)instance;
|
uartPort_t *s = (uartPort_t *)instance;
|
||||||
s->port.txBuffer[s->port.txBufferHead] = ch;
|
s->port.txBuffer[s->port.txBufferHead] = ch;
|
||||||
s->port.txBufferHead = (s->port.txBufferHead + 1) % s->port.txBufferSize;
|
if (s->port.txBufferHead + 1 >= s->port.txBufferSize) {
|
||||||
|
s->port.txBufferHead = 0;
|
||||||
|
} else {
|
||||||
|
s->port.txBufferHead++;
|
||||||
|
}
|
||||||
|
|
||||||
if (s->txDMAChannel) {
|
if (s->txDMAChannel) {
|
||||||
if (!(s->txDMAChannel->CCR & 1))
|
if (!(s->txDMAChannel->CCR & 1))
|
||||||
|
|
|
@ -17,14 +17,14 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// FIXME since serial ports can be used for any function these buffer sizes probably need normalising.
|
// Since serial ports can be used for any function these buffer sizes should be equal
|
||||||
// Code is optimal when buffer sizes are powers of 2 due to use of % and / operators.
|
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
||||||
#define UART1_RX_BUFFER_SIZE 192
|
#define UART1_RX_BUFFER_SIZE 256
|
||||||
#define UART1_TX_BUFFER_SIZE 192
|
#define UART1_TX_BUFFER_SIZE 256
|
||||||
#define UART2_RX_BUFFER_SIZE 192
|
#define UART2_RX_BUFFER_SIZE 256
|
||||||
#define UART2_TX_BUFFER_SIZE 192
|
#define UART2_TX_BUFFER_SIZE 256
|
||||||
#define UART3_RX_BUFFER_SIZE 192
|
#define UART3_RX_BUFFER_SIZE 256
|
||||||
#define UART3_TX_BUFFER_SIZE 192
|
#define UART3_TX_BUFFER_SIZE 256
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
|
|
|
@ -58,14 +58,18 @@ void usartIrqCallback(uartPort_t *s)
|
||||||
if (s->port.callback) {
|
if (s->port.callback) {
|
||||||
s->port.callback(s->USARTx->DR);
|
s->port.callback(s->USARTx->DR);
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR;
|
||||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||||
|
s->port.rxBufferHead = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (SR & USART_FLAG_TXE) {
|
if (SR & USART_FLAG_TXE) {
|
||||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail++];
|
||||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
if (s->port.txBufferTail >= s->port.txBufferSize) {
|
||||||
|
s->port.txBufferTail = 0;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
}
|
}
|
||||||
|
|
|
@ -40,21 +40,39 @@
|
||||||
#define USE_USART1_RX_DMA
|
#define USE_USART1_RX_DMA
|
||||||
//#define USE_USART2_RX_DMA
|
//#define USE_USART2_RX_DMA
|
||||||
//#define USE_USART2_TX_DMA
|
//#define USE_USART2_TX_DMA
|
||||||
|
//#define USE_USART3_RX_DMA
|
||||||
|
//#define USE_USART3_TX_DMA
|
||||||
|
|
||||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
#ifndef UART1_GPIO
|
||||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||||
#define UART1_GPIO GPIOA
|
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
#define UART1_GPIO GPIOA
|
||||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
#define UART1_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||||
|
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef UART2_GPIO
|
||||||
#define UART2_TX_PIN GPIO_Pin_5 // PD5
|
#define UART2_TX_PIN GPIO_Pin_5 // PD5
|
||||||
#define UART2_RX_PIN GPIO_Pin_6 // PD6
|
#define UART2_RX_PIN GPIO_Pin_6 // PD6
|
||||||
#define UART2_GPIO GPIOD
|
#define UART2_GPIO GPIOD
|
||||||
|
#define UART2_GPIO_AF GPIO_AF_7
|
||||||
#define UART2_TX_PINSOURCE GPIO_PinSource5
|
#define UART2_TX_PINSOURCE GPIO_PinSource5
|
||||||
#define UART2_RX_PINSOURCE GPIO_PinSource6
|
#define UART2_RX_PINSOURCE GPIO_PinSource6
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef UART3_GPIO
|
||||||
|
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||||
|
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||||
|
#define UART2_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART3_GPIO GPIOB
|
||||||
|
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||||
|
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||||
|
#endif
|
||||||
|
|
||||||
static uartPort_t uartPort1;
|
static uartPort_t uartPort1;
|
||||||
static uartPort_t uartPort2;
|
static uartPort_t uartPort2;
|
||||||
|
static uartPort_t uartPort3;
|
||||||
|
|
||||||
void uartStartTxDMA(uartPort_t *s);
|
void uartStartTxDMA(uartPort_t *s);
|
||||||
|
|
||||||
|
@ -96,20 +114,20 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
||||||
|
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||||
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
||||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART1_RX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART1_RX_PIN;
|
||||||
GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, UART1_GPIO_AF);
|
||||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_BIDIR) {
|
if (mode & MODE_BIDIR) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||||
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
||||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -173,20 +191,20 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
|
||||||
|
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||||
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
||||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART2_RX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART2_RX_PIN;
|
||||||
GPIO_PinAFConfig(UART2_GPIO, UART2_RX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART2_GPIO, UART2_RX_PINSOURCE, UART2_GPIO_AF);
|
||||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_BIDIR) {
|
if (mode & MODE_BIDIR) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||||
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, GPIO_AF_7);
|
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
||||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -210,6 +228,85 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode)
|
||||||
|
{
|
||||||
|
uartPort_t *s;
|
||||||
|
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
||||||
|
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
||||||
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
GPIO_InitTypeDef GPIO_InitStructure;
|
||||||
|
|
||||||
|
s = &uartPort3;
|
||||||
|
s->port.vTable = uartVTable;
|
||||||
|
|
||||||
|
s->port.baudRate = baudRate;
|
||||||
|
|
||||||
|
s->port.rxBufferSize = UART3_RX_BUFFER_SIZE;
|
||||||
|
s->port.txBufferSize = UART3_TX_BUFFER_SIZE;
|
||||||
|
s->port.rxBuffer = rx3Buffer;
|
||||||
|
s->port.txBuffer = tx3Buffer;
|
||||||
|
|
||||||
|
s->USARTx = USART3;
|
||||||
|
|
||||||
|
#ifdef USE_USART3_RX_DMA
|
||||||
|
s->rxDMAChannel = DMA1_Channel3;
|
||||||
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
|
#endif
|
||||||
|
#ifdef USE_USART3_TX_DMA
|
||||||
|
s->txDMAChannel = DMA1_Channel2;
|
||||||
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
|
||||||
|
|
||||||
|
#if defined(USE_USART3_TX_DMA) || defined(USE_USART3_RX_DMA)
|
||||||
|
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||||
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||||
|
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
||||||
|
|
||||||
|
if (mode & MODE_TX) {
|
||||||
|
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||||
|
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, GPIO_AF_7);
|
||||||
|
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mode & MODE_RX) {
|
||||||
|
GPIO_InitStructure.GPIO_Pin = UART3_RX_PIN;
|
||||||
|
GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, GPIO_AF_7);
|
||||||
|
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mode & MODE_BIDIR) {
|
||||||
|
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||||
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||||
|
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, GPIO_AF_7);
|
||||||
|
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_USART3_TX_DMA
|
||||||
|
// DMA TX Interrupt
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel2_IRQn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_TXDMA);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_TXDMA);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef USE_USART3_RX_DMA
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_RXDMA);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_RXDMA);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return s;
|
||||||
|
}
|
||||||
|
|
||||||
static void handleUsartTxDma(uartPort_t *s)
|
static void handleUsartTxDma(uartPort_t *s)
|
||||||
{
|
{
|
||||||
DMA_Cmd(s->txDMAChannel, DISABLE);
|
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||||
|
@ -238,6 +335,15 @@ void DMA1_Channel7_IRQHandler(void)
|
||||||
handleUsartTxDma(s);
|
handleUsartTxDma(s);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// USART3 Tx DMA Handler
|
||||||
|
void DMA1_Channel2_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &uartPort3;
|
||||||
|
DMA_ClearITPendingBit(DMA1_IT_TC2);
|
||||||
|
DMA_Cmd(DMA1_Channel2, DISABLE);
|
||||||
|
handleUsartTxDma(s);
|
||||||
|
}
|
||||||
|
|
||||||
void usartIrqHandler(uartPort_t *s)
|
void usartIrqHandler(uartPort_t *s)
|
||||||
{
|
{
|
||||||
uint32_t ISR = s->USARTx->ISR;
|
uint32_t ISR = s->USARTx->ISR;
|
||||||
|
@ -246,15 +352,19 @@ void usartIrqHandler(uartPort_t *s)
|
||||||
if (s->port.callback) {
|
if (s->port.callback) {
|
||||||
s->port.callback(s->USARTx->RDR);
|
s->port.callback(s->USARTx->RDR);
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->RDR;
|
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
|
||||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||||
|
s->port.rxBufferHead = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!s->txDMAChannel && (ISR & USART_FLAG_TXE)) {
|
if (!s->txDMAChannel && (ISR & USART_FLAG_TXE)) {
|
||||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||||
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail++]);
|
||||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
if (s->port.txBufferTail >= s->port.txBufferSize) {
|
||||||
|
s->port.txBufferTail = 0;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
}
|
}
|
||||||
|
@ -280,3 +390,10 @@ void USART2_IRQHandler(void)
|
||||||
usartIrqHandler(s);
|
usartIrqHandler(s);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void USART3_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &uartPort3;
|
||||||
|
|
||||||
|
usartIrqHandler(s);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -30,6 +30,7 @@ void failureMode(uint8_t mode);
|
||||||
// bootloader/IAP
|
// bootloader/IAP
|
||||||
void systemReset(void);
|
void systemReset(void);
|
||||||
void systemResetToBootloader(void);
|
void systemResetToBootloader(void);
|
||||||
|
bool isMPUSoftReset(void);
|
||||||
|
|
||||||
void enableGPIOPowerUsageAndNoiseReductions(void);
|
void enableGPIOPowerUsageAndNoiseReductions(void);
|
||||||
// current crystal frequency - 8 or 12MHz
|
// current crystal frequency - 8 or 12MHz
|
||||||
|
|
|
@ -22,11 +22,19 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
|
#include "system.h"
|
||||||
|
|
||||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||||
|
#define BKP_SOFTRESET (0x50F7B007)
|
||||||
|
|
||||||
void systemReset(void)
|
void systemReset(void)
|
||||||
{
|
{
|
||||||
|
// write magic value that we're doing a soft reset
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
|
||||||
|
PWR->CR |= PWR_CR_DBP;
|
||||||
|
*((uint16_t *)BKP_BASE + 0x04) = BKP_SOFTRESET & 0xffff;
|
||||||
|
*((uint16_t *)BKP_BASE + 0x08) = (BKP_SOFTRESET & 0xffff0000) >> 16;
|
||||||
|
|
||||||
// Generate system reset
|
// Generate system reset
|
||||||
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
|
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
|
||||||
}
|
}
|
||||||
|
@ -52,3 +60,11 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||||
gpioInit(GPIOB, &gpio);
|
gpioInit(GPIOB, &gpio);
|
||||||
gpioInit(GPIOC, &gpio);
|
gpioInit(GPIOC, &gpio);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isMPUSoftReset(void)
|
||||||
|
{
|
||||||
|
if ((*((uint16_t *)BKP_BASE + 0x04) | *((uint16_t *)BKP_BASE + 0x08) << 16) == BKP_SOFTRESET)
|
||||||
|
return true;
|
||||||
|
else
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
|
@ -67,3 +67,11 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||||
gpioInit(GPIOE, &gpio);
|
gpioInit(GPIOE, &gpio);
|
||||||
gpioInit(GPIOF, &gpio);
|
gpioInit(GPIOF, &gpio);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isMPUSoftReset(void)
|
||||||
|
{
|
||||||
|
if (RCC->CSR & RCC_CSR_SFTRSTF)
|
||||||
|
return true;
|
||||||
|
else
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
|
@ -80,7 +80,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S3_OUT
|
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S3_OUT
|
||||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP}, // S4_OUT
|
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP}, // S4_OUT
|
||||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
|
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
|
||||||
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF_PP}, // S6_OUT
|
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF_PP} // S6_OUT
|
||||||
};
|
};
|
||||||
|
|
||||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
||||||
|
@ -164,7 +164,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PA2 - untested
|
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PA2 - untested
|
||||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PA3 - untested
|
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PA3 - untested
|
||||||
{ TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PA6 - untested
|
{ TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PA6 - untested
|
||||||
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PA7 - untested
|
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1} // PA7 - untested
|
||||||
};
|
};
|
||||||
|
|
||||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17))
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17))
|
||||||
|
@ -175,6 +175,51 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef SPARKY
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
//
|
||||||
|
// 6 x 3 pin headers
|
||||||
|
//
|
||||||
|
|
||||||
|
{ TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
|
||||||
|
{ TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_1}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
|
||||||
|
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||||
|
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||||
|
{ TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||||
|
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||||
|
|
||||||
|
//
|
||||||
|
// 6 pin header
|
||||||
|
//
|
||||||
|
|
||||||
|
// PWM7-10
|
||||||
|
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||||
|
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||||
|
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM9 - PA4 - *TIM3_CH2
|
||||||
|
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||||
|
|
||||||
|
//
|
||||||
|
// PPM PORT - Also USART2 RX (AF5)
|
||||||
|
//
|
||||||
|
|
||||||
|
{ TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_1} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||||
|
//{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_9} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||||
|
|
||||||
|
// USART3 RX/TX
|
||||||
|
// RX conflicts with PPM port
|
||||||
|
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11
|
||||||
|
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
|
||||||
|
|
||||||
|
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
|
||||||
|
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17)
|
||||||
|
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
|
#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
|
||||||
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
||||||
|
|
||||||
|
@ -719,14 +764,6 @@ void timerInit(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if 0
|
|
||||||
#if defined(STMF3DISCOVERY) || defined(NAZE32PRO)
|
|
||||||
// FIXME move these where they are needed.
|
|
||||||
GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_2);
|
|
||||||
GPIO_PinAFConfig(GPIOB, GPIO_PinSource1, GPIO_AF_2);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// initialize timer channel structures
|
// initialize timer channel structures
|
||||||
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||||
timerChannelInfo[i].type = TYPE_FREE;
|
timerChannelInfo[i].type = TYPE_FREE;
|
||||||
|
|
|
@ -17,6 +17,10 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef SPARKY
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef CHEBUZZF3
|
#ifdef CHEBUZZF3
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 18
|
#define USABLE_TIMER_CHANNEL_COUNT 18
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -246,12 +246,24 @@ static int32_t nav_bearing;
|
||||||
// saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home
|
// saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home
|
||||||
static int16_t nav_takeoff_bearing;
|
static int16_t nav_takeoff_bearing;
|
||||||
|
|
||||||
|
void GPS_calculateDistanceAndDirectionToHome(void)
|
||||||
|
{
|
||||||
|
if (STATE(GPS_FIX_HOME)) { // If we don't have home set, do not display anything
|
||||||
|
uint32_t dist;
|
||||||
|
int32_t dir;
|
||||||
|
GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_home[LAT], &GPS_home[LON], &dist, &dir);
|
||||||
|
GPS_distanceToHome = dist / 100;
|
||||||
|
GPS_directionToHome = dir / 100;
|
||||||
|
} else {
|
||||||
|
GPS_distanceToHome = 0;
|
||||||
|
GPS_directionToHome = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void onGpsNewData(void)
|
void onGpsNewData(void)
|
||||||
{
|
{
|
||||||
int axis;
|
int axis;
|
||||||
static uint32_t nav_loopTimer;
|
static uint32_t nav_loopTimer;
|
||||||
uint32_t dist;
|
|
||||||
int32_t dir;
|
|
||||||
uint16_t speed;
|
uint16_t speed;
|
||||||
|
|
||||||
|
|
||||||
|
@ -261,8 +273,10 @@ void onGpsNewData(void)
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED))
|
if (!ARMING_FLAG(ARMED))
|
||||||
DISABLE_STATE(GPS_FIX_HOME);
|
DISABLE_STATE(GPS_FIX_HOME);
|
||||||
|
|
||||||
if (!STATE(GPS_FIX_HOME) && ARMING_FLAG(ARMED))
|
if (!STATE(GPS_FIX_HOME) && ARMING_FLAG(ARMED))
|
||||||
GPS_reset_home_position();
|
GPS_reset_home_position();
|
||||||
|
|
||||||
// Apply moving average filter to GPS data
|
// Apply moving average filter to GPS data
|
||||||
#if defined(GPS_FILTERING)
|
#if defined(GPS_FILTERING)
|
||||||
GPS_filter_index = (GPS_filter_index + 1) % GPS_FILTER_VECTOR_LENGTH;
|
GPS_filter_index = (GPS_filter_index + 1) % GPS_FILTER_VECTOR_LENGTH;
|
||||||
|
@ -284,22 +298,17 @@ void onGpsNewData(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
// dTnav calculation
|
|
||||||
|
//
|
||||||
|
// Calculate time delta for navigation loop, range 0-1.0f, in seconds
|
||||||
|
//
|
||||||
// Time for calculating x,y speed and navigation pids
|
// Time for calculating x,y speed and navigation pids
|
||||||
dTnav = (float)(millis() - nav_loopTimer) / 1000.0f;
|
dTnav = (float)(millis() - nav_loopTimer) / 1000.0f;
|
||||||
nav_loopTimer = millis();
|
nav_loopTimer = millis();
|
||||||
// prevent runup from bad GPS
|
// prevent runup from bad GPS
|
||||||
dTnav = min(dTnav, 1.0f);
|
dTnav = min(dTnav, 1.0f);
|
||||||
|
|
||||||
// calculate distance and bearings for gui and other stuff continously - From home to copter
|
GPS_calculateDistanceAndDirectionToHome();
|
||||||
GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_home[LAT], &GPS_home[LON], &dist, &dir);
|
|
||||||
GPS_distanceToHome = dist / 100;
|
|
||||||
GPS_directionToHome = dir / 100;
|
|
||||||
|
|
||||||
if (!STATE(GPS_FIX_HOME)) { // If we don't have home set, do not display anything
|
|
||||||
GPS_distanceToHome = 0;
|
|
||||||
GPS_directionToHome = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// calculate the current velocity based on gps coordinates continously to get a valid speed at the moment when we start navigating
|
// calculate the current velocity based on gps coordinates continously to get a valid speed at the moment when we start navigating
|
||||||
GPS_calc_velocity();
|
GPS_calc_velocity();
|
||||||
|
@ -436,16 +445,19 @@ static bool check_missed_wp(void)
|
||||||
return (abs(temp) > 10000); // we passed the waypoint by 100 degrees
|
return (abs(temp) > 10000); // we passed the waypoint by 100 degrees
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#define DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR_IN_HUNDREDS_OF_KILOMETERS 1.113195f
|
||||||
|
#define TAN_89_99_DEGREES 5729.57795f
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////////
|
||||||
// Get distance between two points in cm
|
// Get distance between two points in cm
|
||||||
// Get bearing from pos1 to pos2, returns an 1deg = 100 precision
|
// Get bearing from pos1 to pos2, returns an 1deg = 100 precision
|
||||||
static void GPS_distance_cm_bearing(int32_t * lat1, int32_t * lon1, int32_t * lat2, int32_t * lon2, uint32_t * dist, int32_t * bearing)
|
static void GPS_distance_cm_bearing(int32_t *currentLat1, int32_t *currentLon1, int32_t *destinationLat2, int32_t *destinationLon2, uint32_t *dist, int32_t *bearing)
|
||||||
{
|
{
|
||||||
float dLat = *lat2 - *lat1; // difference of latitude in 1/10 000 000 degrees
|
float dLat = *destinationLat2 - *currentLat1; // difference of latitude in 1/10 000 000 degrees
|
||||||
float dLon = (float)(*lon2 - *lon1) * GPS_scaleLonDown;
|
float dLon = (float)(*destinationLon2 - *currentLon1) * GPS_scaleLonDown;
|
||||||
*dist = sqrtf(sq(dLat) + sq(dLon)) * 1.113195f;
|
*dist = sqrtf(sq(dLat) + sq(dLon)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR_IN_HUNDREDS_OF_KILOMETERS;
|
||||||
|
|
||||||
*bearing = 9000.0f + atan2f(-dLat, dLon) * 5729.57795f; // Convert the output radians to 100xdeg
|
*bearing = 9000.0f + atan2f(-dLat, dLon) * TAN_89_99_DEGREES; // Convert the output radians to 100xdeg
|
||||||
if (*bearing < 0)
|
if (*bearing < 0)
|
||||||
*bearing += 36000;
|
*bearing += 36000;
|
||||||
}
|
}
|
||||||
|
@ -467,15 +479,15 @@ static void GPS_distance_cm_bearing(int32_t * lat1, int32_t * lon1, int32_t * la
|
||||||
static void GPS_calc_velocity(void)
|
static void GPS_calc_velocity(void)
|
||||||
{
|
{
|
||||||
static int16_t speed_old[2] = { 0, 0 };
|
static int16_t speed_old[2] = { 0, 0 };
|
||||||
static int32_t last[2] = { 0, 0 };
|
static int32_t last_coord[2] = { 0, 0 };
|
||||||
static uint8_t init = 0;
|
static uint8_t init = 0;
|
||||||
// y_GPS_speed positve = Up
|
// y_GPS_speed positive = Up
|
||||||
// x_GPS_speed positve = Right
|
// x_GPS_speed positive = Right
|
||||||
|
|
||||||
if (init) {
|
if (init) {
|
||||||
float tmp = 1.0f / dTnav;
|
float tmp = 1.0f / dTnav;
|
||||||
actual_speed[GPS_X] = (float)(GPS_coord[LON] - last[LON]) * GPS_scaleLonDown * tmp;
|
actual_speed[GPS_X] = (float)(GPS_coord[LON] - last_coord[LON]) * GPS_scaleLonDown * tmp;
|
||||||
actual_speed[GPS_Y] = (float)(GPS_coord[LAT] - last[LAT]) * tmp;
|
actual_speed[GPS_Y] = (float)(GPS_coord[LAT] - last_coord[LAT]) * tmp;
|
||||||
|
|
||||||
actual_speed[GPS_X] = (actual_speed[GPS_X] + speed_old[GPS_X]) / 2;
|
actual_speed[GPS_X] = (actual_speed[GPS_X] + speed_old[GPS_X]) / 2;
|
||||||
actual_speed[GPS_Y] = (actual_speed[GPS_Y] + speed_old[GPS_Y]) / 2;
|
actual_speed[GPS_Y] = (actual_speed[GPS_Y] + speed_old[GPS_Y]) / 2;
|
||||||
|
@ -485,8 +497,8 @@ static void GPS_calc_velocity(void)
|
||||||
}
|
}
|
||||||
init = 1;
|
init = 1;
|
||||||
|
|
||||||
last[LON] = GPS_coord[LON];
|
last_coord[LON] = GPS_coord[LON];
|
||||||
last[LAT] = GPS_coord[LAT];
|
last_coord[LAT] = GPS_coord[LAT];
|
||||||
}
|
}
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -648,43 +660,73 @@ void updateGpsStateForHomeAndHoldMode(void)
|
||||||
|
|
||||||
void updateGpsWaypointsAndMode(void)
|
void updateGpsWaypointsAndMode(void)
|
||||||
{
|
{
|
||||||
static uint8_t GPSNavReset = 1;
|
bool resetNavNow = false;
|
||||||
|
|
||||||
if (STATE(GPS_FIX) && GPS_numSat >= 5) {
|
if (STATE(GPS_FIX) && GPS_numSat >= 5) {
|
||||||
// if both GPS_HOME & GPS_HOLD are checked => GPS_HOME is the priority
|
|
||||||
|
//
|
||||||
|
// process HOME mode
|
||||||
|
//
|
||||||
|
// HOME mode takes priority over HOLD mode.
|
||||||
|
|
||||||
if (IS_RC_MODE_ACTIVE(BOXGPSHOME)) {
|
if (IS_RC_MODE_ACTIVE(BOXGPSHOME)) {
|
||||||
if (!FLIGHT_MODE(GPS_HOME_MODE)) {
|
if (!FLIGHT_MODE(GPS_HOME_MODE)) {
|
||||||
|
|
||||||
|
// Transition to HOME mode
|
||||||
ENABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
ENABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
||||||
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
||||||
GPSNavReset = 0;
|
|
||||||
GPS_set_next_wp(&GPS_home[LAT], &GPS_home[LON]);
|
GPS_set_next_wp(&GPS_home[LAT], &GPS_home[LON]);
|
||||||
nav_mode = NAV_MODE_WP;
|
nav_mode = NAV_MODE_WP;
|
||||||
|
resetNavNow = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
DISABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
if (FLIGHT_MODE(GPS_HOME_MODE)) {
|
||||||
|
|
||||||
|
// Transition from HOME mode
|
||||||
|
DISABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
||||||
|
nav_mode = NAV_MODE_NONE;
|
||||||
|
resetNavNow = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// process HOLD mode
|
||||||
|
//
|
||||||
|
|
||||||
if (IS_RC_MODE_ACTIVE(BOXGPSHOLD) && areSticksInApModePosition(gpsProfile->ap_mode)) {
|
if (IS_RC_MODE_ACTIVE(BOXGPSHOLD) && areSticksInApModePosition(gpsProfile->ap_mode)) {
|
||||||
if (!FLIGHT_MODE(GPS_HOLD_MODE)) {
|
if (!FLIGHT_MODE(GPS_HOLD_MODE)) {
|
||||||
|
|
||||||
|
// Transition to HOLD mode
|
||||||
ENABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
ENABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
||||||
GPSNavReset = 0;
|
|
||||||
GPS_hold[LAT] = GPS_coord[LAT];
|
GPS_hold[LAT] = GPS_coord[LAT];
|
||||||
GPS_hold[LON] = GPS_coord[LON];
|
GPS_hold[LON] = GPS_coord[LON];
|
||||||
GPS_set_next_wp(&GPS_hold[LAT], &GPS_hold[LON]);
|
GPS_set_next_wp(&GPS_hold[LAT], &GPS_hold[LON]);
|
||||||
nav_mode = NAV_MODE_POSHOLD;
|
nav_mode = NAV_MODE_POSHOLD;
|
||||||
|
resetNavNow = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
if (FLIGHT_MODE(GPS_HOLD_MODE)) {
|
||||||
// both boxes are unselected here, nav is reset if not already done
|
|
||||||
if (GPSNavReset == 0) {
|
// Transition from HOLD mode
|
||||||
GPSNavReset = 1;
|
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
||||||
GPS_reset_nav();
|
nav_mode = NAV_MODE_NONE;
|
||||||
|
resetNavNow = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
DISABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
if (FLIGHT_MODE(GPS_HOLD_MODE | GPS_HOME_MODE)) {
|
||||||
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
|
||||||
nav_mode = NAV_MODE_NONE;
|
// Transition from HOME or HOLD mode
|
||||||
|
DISABLE_FLIGHT_MODE(GPS_HOME_MODE);
|
||||||
|
DISABLE_FLIGHT_MODE(GPS_HOLD_MODE);
|
||||||
|
nav_mode = NAV_MODE_NONE;
|
||||||
|
resetNavNow = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (resetNavNow) {
|
||||||
|
GPS_reset_nav();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -24,6 +24,8 @@ typedef enum {
|
||||||
NAV_MODE_WP
|
NAV_MODE_WP
|
||||||
} navigationMode_e;
|
} navigationMode_e;
|
||||||
|
|
||||||
|
// FIXME ap_mode is badly named, it's a value that is compared to rcCommand, not a flag at it's name implies.
|
||||||
|
|
||||||
typedef struct gpsProfile_s {
|
typedef struct gpsProfile_s {
|
||||||
uint16_t gps_wp_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
uint16_t gps_wp_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
||||||
uint8_t gps_lpf; // Low pass filter cut frequency for derivative calculation (default 20Hz)
|
uint8_t gps_lpf; // Low pass filter cut frequency for derivative calculation (default 20Hz)
|
||||||
|
|
|
@ -41,6 +41,11 @@
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
|
#ifdef GPS
|
||||||
|
#include "io/gps.h"
|
||||||
|
#include "flight/navigation.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
|
|
||||||
|
@ -67,19 +72,6 @@ static rxConfig_t *rxConfig;
|
||||||
|
|
||||||
static char lineBuffer[SCREEN_CHARACTER_COLUMN_COUNT + 1];
|
static char lineBuffer[SCREEN_CHARACTER_COLUMN_COUNT + 1];
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
PAGE_WELCOME,
|
|
||||||
PAGE_ARMED,
|
|
||||||
PAGE_BATTERY,
|
|
||||||
PAGE_SENSORS,
|
|
||||||
PAGE_RX,
|
|
||||||
PAGE_PROFILE
|
|
||||||
#ifdef ENABLE_DEBUG_OLED_PAGE
|
|
||||||
,
|
|
||||||
PAGE_DEBUG
|
|
||||||
#endif
|
|
||||||
} pageId_e;
|
|
||||||
|
|
||||||
const char* pageTitles[] = {
|
const char* pageTitles[] = {
|
||||||
"CLEANFLIGHT",
|
"CLEANFLIGHT",
|
||||||
"ARMED",
|
"ARMED",
|
||||||
|
@ -87,9 +79,11 @@ const char* pageTitles[] = {
|
||||||
"SENSORS",
|
"SENSORS",
|
||||||
"RX",
|
"RX",
|
||||||
"PROFILE"
|
"PROFILE"
|
||||||
|
#ifdef GPS
|
||||||
|
,"GPS"
|
||||||
|
#endif
|
||||||
#ifdef ENABLE_DEBUG_OLED_PAGE
|
#ifdef ENABLE_DEBUG_OLED_PAGE
|
||||||
,
|
,"DEBUG"
|
||||||
"DEBUG"
|
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -97,12 +91,14 @@ const char* pageTitles[] = {
|
||||||
|
|
||||||
const uint8_t cyclePageIds[] = {
|
const uint8_t cyclePageIds[] = {
|
||||||
PAGE_PROFILE,
|
PAGE_PROFILE,
|
||||||
|
#ifdef GPS
|
||||||
|
PAGE_GPS,
|
||||||
|
#endif
|
||||||
PAGE_RX,
|
PAGE_RX,
|
||||||
PAGE_BATTERY,
|
PAGE_BATTERY,
|
||||||
PAGE_SENSORS
|
PAGE_SENSORS
|
||||||
#ifdef ENABLE_DEBUG_OLED_PAGE
|
#ifdef ENABLE_DEBUG_OLED_PAGE
|
||||||
,
|
,PAGE_DEBUG,
|
||||||
PAGE_DEBUG,
|
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -286,6 +282,68 @@ void showProfilePage(void)
|
||||||
i2c_OLED_send_string(lineBuffer);
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0]))
|
||||||
|
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
|
||||||
|
|
||||||
|
#ifdef GPS
|
||||||
|
void showGpsPage() {
|
||||||
|
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
|
||||||
|
|
||||||
|
i2c_OLED_set_xy(max(0, SATELLITE_GRAPH_LEFT_OFFSET), rowIndex++);
|
||||||
|
|
||||||
|
uint32_t index;
|
||||||
|
for (index = 0; index < SATELLITE_COUNT && index < SCREEN_CHARACTER_COLUMN_COUNT; index++) {
|
||||||
|
uint8_t bargraphValue = ((uint16_t) GPS_svinfo_cno[index] * VERTICAL_BARGRAPH_CHARACTER_COUNT) / (GPS_DBHZ_MAX - 1);
|
||||||
|
bargraphValue = min(bargraphValue, VERTICAL_BARGRAPH_CHARACTER_COUNT - 1);
|
||||||
|
i2c_OLED_send_char(VERTICAL_BARGRAPH_ZERO_CHARACTER + bargraphValue);
|
||||||
|
}
|
||||||
|
|
||||||
|
char fixChar = STATE(GPS_FIX) ? 'Y' : 'N';
|
||||||
|
tfp_sprintf(lineBuffer, "Satellites: %d Fix: %c", GPS_numSat, fixChar);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
tfp_sprintf(lineBuffer, "Lat: %d Lon: %d", GPS_coord[LAT] / GPS_DEGREES_DIVIDER, GPS_coord[LON] / GPS_DEGREES_DIVIDER);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
tfp_sprintf(lineBuffer, "Spd: %d cm/s GC: %d", GPS_speed, GPS_ground_course);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
tfp_sprintf(lineBuffer, "RX: %d Delta: %d", GPS_packetCount, gpsData.lastMessage - gpsData.lastLastMessage);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
tfp_sprintf(lineBuffer, "ERRs: %d TOs: %d", gpsData.errors, gpsData.timeouts);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
strncpy(lineBuffer, gpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
|
||||||
|
#ifdef GPS_PH_DEBUG
|
||||||
|
tfp_sprintf(lineBuffer, "Angles: P:%d R:%d", GPS_angle[PITCH], GPS_angle[ROLL]);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
tfp_sprintf(lineBuffer, "%d %d %d %d", debug[0], debug[1], debug[2], debug[3]);
|
||||||
|
padLineBuffer();
|
||||||
|
i2c_OLED_set_line(rowIndex++);
|
||||||
|
i2c_OLED_send_string(lineBuffer);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void showBatteryPage(void)
|
void showBatteryPage(void)
|
||||||
{
|
{
|
||||||
|
@ -386,7 +444,8 @@ void updateDisplay(void)
|
||||||
pageState.pageId = pageState.pageIdBeforeArming;
|
pageState.pageId = pageState.pageIdBeforeArming;
|
||||||
}
|
}
|
||||||
|
|
||||||
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) || ((int32_t)(now - pageState.nextPageAt) >= 0L);
|
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) ||
|
||||||
|
(((int32_t)(now - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)));
|
||||||
if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) {
|
if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) {
|
||||||
pageState.cycleIndex++;
|
pageState.cycleIndex++;
|
||||||
pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT;
|
pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT;
|
||||||
|
@ -419,6 +478,15 @@ void updateDisplay(void)
|
||||||
case PAGE_PROFILE:
|
case PAGE_PROFILE:
|
||||||
showProfilePage();
|
showProfilePage();
|
||||||
break;
|
break;
|
||||||
|
#ifdef GPS
|
||||||
|
case PAGE_GPS:
|
||||||
|
if (feature(FEATURE_GPS)) {
|
||||||
|
showGpsPage();
|
||||||
|
} else {
|
||||||
|
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
#ifdef ENABLE_DEBUG_OLED_PAGE
|
#ifdef ENABLE_DEBUG_OLED_PAGE
|
||||||
case PAGE_DEBUG:
|
case PAGE_DEBUG:
|
||||||
showDebugPage();
|
showDebugPage();
|
||||||
|
@ -430,6 +498,12 @@ void updateDisplay(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void displaySetPage(pageId_e pageId)
|
||||||
|
{
|
||||||
|
pageState.pageId = pageId;
|
||||||
|
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
|
||||||
|
}
|
||||||
|
|
||||||
void displayInit(rxConfig_t *rxConfigToUse)
|
void displayInit(rxConfig_t *rxConfigToUse)
|
||||||
{
|
{
|
||||||
delay(200);
|
delay(200);
|
||||||
|
@ -439,23 +513,32 @@ void displayInit(rxConfig_t *rxConfigToUse)
|
||||||
rxConfig = rxConfigToUse;
|
rxConfig = rxConfigToUse;
|
||||||
|
|
||||||
memset(&pageState, 0, sizeof(pageState));
|
memset(&pageState, 0, sizeof(pageState));
|
||||||
pageState.pageId = PAGE_WELCOME;
|
displaySetPage(PAGE_WELCOME);
|
||||||
|
|
||||||
updateDisplay();
|
updateDisplay();
|
||||||
|
|
||||||
displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5));
|
displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5));
|
||||||
}
|
}
|
||||||
|
|
||||||
void displaySetNextPageChangeAt(uint32_t futureMicros) {
|
void displayShowFixedPage(pageId_e pageId)
|
||||||
|
{
|
||||||
|
displaySetPage(pageId);
|
||||||
|
displayDisablePageCycling();
|
||||||
|
}
|
||||||
|
|
||||||
|
void displaySetNextPageChangeAt(uint32_t futureMicros)
|
||||||
|
{
|
||||||
pageState.nextPageAt = futureMicros;
|
pageState.nextPageAt = futureMicros;
|
||||||
}
|
}
|
||||||
|
|
||||||
void displayEnablePageCycling(void) {
|
void displayEnablePageCycling(void)
|
||||||
|
{
|
||||||
pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED;
|
pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED;
|
||||||
pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page
|
pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page
|
||||||
}
|
}
|
||||||
|
|
||||||
void displayDisablePageCycling(void) {
|
void displayDisablePageCycling(void)
|
||||||
|
{
|
||||||
pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED;
|
pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -15,8 +15,24 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
PAGE_WELCOME,
|
||||||
|
PAGE_ARMED,
|
||||||
|
PAGE_BATTERY,
|
||||||
|
PAGE_SENSORS,
|
||||||
|
PAGE_RX,
|
||||||
|
PAGE_PROFILE,
|
||||||
|
PAGE_GPS
|
||||||
|
#ifdef ENABLE_DEBUG_OLED_PAGE
|
||||||
|
,
|
||||||
|
PAGE_DEBUG
|
||||||
|
#endif
|
||||||
|
} pageId_e;
|
||||||
|
|
||||||
void updateDisplay(void);
|
void updateDisplay(void);
|
||||||
|
|
||||||
|
void displayShowFixedPage(pageId_e pageId);
|
||||||
|
|
||||||
void displayEnablePageCycling(void);
|
void displayEnablePageCycling(void);
|
||||||
void displayDisablePageCycling(void);
|
void displayDisablePageCycling(void);
|
||||||
void displaySetNextPageChangeAt(uint32_t futureMicros);
|
void displaySetNextPageChangeAt(uint32_t futureMicros);
|
||||||
|
|
|
@ -24,6 +24,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
@ -46,13 +48,29 @@
|
||||||
#include "flight/gps_conversion.h"
|
#include "flight/gps_conversion.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
|
#include "io/display.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
|
||||||
extern int16_t debug[4];
|
extern int16_t debug[4];
|
||||||
|
|
||||||
|
|
||||||
|
#define LOG_ERROR '?'
|
||||||
|
#define LOG_IGNORED '!'
|
||||||
|
#define LOG_SKIPPED '>'
|
||||||
|
#define LOG_NMEA_GGA 'g'
|
||||||
|
#define LOG_NMEA_RMC 'r'
|
||||||
|
#define LOG_UBLOX_SOL 'O'
|
||||||
|
#define LOG_UBLOX_STATUS 'S'
|
||||||
|
#define LOG_UBLOX_SVINFO 'I'
|
||||||
|
#define LOG_UBLOX_POSLLH 'P'
|
||||||
|
#define LOG_UBLOX_VELNED 'V'
|
||||||
|
|
||||||
|
char gpsPacketLog[GPS_PACKET_LOG_ENTRY_COUNT];
|
||||||
|
static char *gpsPacketLogChar = gpsPacketLog;
|
||||||
// **********************
|
// **********************
|
||||||
// GPS
|
// GPS
|
||||||
// **********************
|
// **********************
|
||||||
|
@ -60,6 +78,7 @@ int32_t GPS_coord[2]; // LAT/LON
|
||||||
|
|
||||||
uint8_t GPS_numSat;
|
uint8_t GPS_numSat;
|
||||||
uint16_t GPS_hdop = 9999; // Compute GPS quality signal
|
uint16_t GPS_hdop = 9999; // Compute GPS quality signal
|
||||||
|
uint32_t GPS_packetCount = 0;
|
||||||
uint8_t GPS_update = 0; // it's a binary toggle to distinct a GPS position update
|
uint8_t GPS_update = 0; // it's a binary toggle to distinct a GPS position update
|
||||||
|
|
||||||
uint16_t GPS_altitude; // altitude in 0.1m
|
uint16_t GPS_altitude; // altitude in 0.1m
|
||||||
|
@ -78,7 +97,7 @@ static gpsConfig_t *gpsConfig;
|
||||||
#define GPS_TIMEOUT (2500)
|
#define GPS_TIMEOUT (2500)
|
||||||
// How many entries in gpsInitData array below
|
// How many entries in gpsInitData array below
|
||||||
#define GPS_INIT_ENTRIES (GPS_BAUDRATE_MAX + 1)
|
#define GPS_INIT_ENTRIES (GPS_BAUDRATE_MAX + 1)
|
||||||
#define GPS_BAUDRATE_CHATE_DELAY (100)
|
#define GPS_BAUDRATE_CHANGE_DELAY (200)
|
||||||
|
|
||||||
static serialConfig_t *serialConfig;
|
static serialConfig_t *serialConfig;
|
||||||
static serialPort_t *gpsPort;
|
static serialPort_t *gpsPort;
|
||||||
|
@ -97,7 +116,7 @@ static const gpsInitData_t gpsInitData[] = {
|
||||||
{ GPS_BAUDRATE_38400, 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" },
|
{ GPS_BAUDRATE_38400, 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" },
|
||||||
{ GPS_BAUDRATE_19200, 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" },
|
{ GPS_BAUDRATE_19200, 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" },
|
||||||
// 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed
|
// 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed
|
||||||
{ GPS_BAUDRATE_9600, 9600, "", "" }
|
{ GPS_BAUDRATE_9600, 9600, "$PUBX,41,1,0003,0001,9600,0*16\r\n", "" }
|
||||||
};
|
};
|
||||||
|
|
||||||
#define GPS_INIT_DATA_ENTRY_COUNT (sizeof(gpsInitData) / sizeof(gpsInitData[0]))
|
#define GPS_INIT_DATA_ENTRY_COUNT (sizeof(gpsInitData) / sizeof(gpsInitData[0]))
|
||||||
|
@ -105,17 +124,29 @@ static const gpsInitData_t gpsInitData[] = {
|
||||||
#define DEFAULT_BAUD_RATE_INDEX 0
|
#define DEFAULT_BAUD_RATE_INDEX 0
|
||||||
|
|
||||||
static const uint8_t ubloxInit[] = {
|
static const uint8_t ubloxInit[] = {
|
||||||
|
|
||||||
|
0xB5, 0x62, 0x06, 0x24, 0x24, 0x00, 0xFF, 0xFF, 0x03, 0x03, 0x00, // CFG-NAV5 - Set engine settings
|
||||||
|
0x00, 0x00, 0x00, 0x10, 0x27, 0x00, 0x00, 0x05, 0x00, 0xFA, 0x00, // Collected by resetting a GPS unit to defaults. Changing mode to Pedistrian and
|
||||||
|
0xFA, 0x00, 0x64, 0x00, 0x2C, 0x01, 0x00, 0x3C, 0x00, 0x00, 0x00, // capturing the data from the U-Center binary console.
|
||||||
|
0x00, 0xC8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0xC2,
|
||||||
|
|
||||||
|
// DISABLE NMEA messages
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // VGS: Course over ground and Ground speed
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // VGS: Course over ground and Ground speed
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, // GSV: GNSS Satellites in View
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, // GSV: GNSS Satellites in View
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11, // GLL: Latitude and longitude, with time of position fix and status
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11, // GLL: Latitude and longitude, with time of position fix and status
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F, // GGA: Global positioning system fix data
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F, // GGA: Global positioning system fix data
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13, // GSA: GNSS DOP and Active Satellites
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13, // GSA: GNSS DOP and Active Satellites
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17, // RMC: Recommended Minimum data
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17, // RMC: Recommended Minimum data
|
||||||
|
|
||||||
|
// Enable UBLOX messages
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47, // set POSLLH MSG rate
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47, // set POSLLH MSG rate
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49, // set STATUS MSG rate
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49, // set STATUS MSG rate
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F, // set SOL MSG rate
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F, // set SOL MSG rate
|
||||||
|
//0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x30, 0x01, 0x3C, 0xA3, // set SVINFO MSG rate (every cycle - high bandwidth)
|
||||||
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x30, 0x05, 0x40, 0xA7, // set SVINFO MSG rate (evey 5 cycles - low bandwidth)
|
||||||
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67, // set VELNED MSG rate
|
0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67, // set VELNED MSG rate
|
||||||
0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A, // set rate to 5Hz
|
|
||||||
|
0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A, // set rate to 5Hz (measurement period: 200ms, navigation rate: 1 cycle)
|
||||||
};
|
};
|
||||||
|
|
||||||
// UBlox 6 Protocol documentation - GPS.G6-SW-10018-F
|
// UBlox 6 Protocol documentation - GPS.G6-SW-10018-F
|
||||||
|
@ -153,6 +184,16 @@ enum {
|
||||||
|
|
||||||
gpsData_t gpsData;
|
gpsData_t gpsData;
|
||||||
|
|
||||||
|
|
||||||
|
static void shiftPacketLog(void)
|
||||||
|
{
|
||||||
|
uint32_t i;
|
||||||
|
|
||||||
|
for (i = sizeof(gpsPacketLog) - 1; i > 0 ; i--) {
|
||||||
|
gpsPacketLog[i] = gpsPacketLog[i-1];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void gpsNewData(uint16_t c);
|
static void gpsNewData(uint16_t c);
|
||||||
static bool gpsNewFrameNMEA(char c);
|
static bool gpsNewFrameNMEA(char c);
|
||||||
static bool gpsNewFrameUBLOX(uint8_t data);
|
static bool gpsNewFrameUBLOX(uint8_t data);
|
||||||
|
@ -179,13 +220,17 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
gpsData.errors = 0;
|
||||||
|
gpsData.timeouts = 0;
|
||||||
|
|
||||||
|
memset(gpsPacketLog, 0x00, sizeof(gpsPacketLog));
|
||||||
|
|
||||||
gpsConfig = initialGpsConfig;
|
gpsConfig = initialGpsConfig;
|
||||||
|
|
||||||
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
|
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
|
||||||
gpsSetState(GPS_UNKNOWN);
|
gpsSetState(GPS_UNKNOWN);
|
||||||
|
|
||||||
gpsData.lastMessage = millis();
|
gpsData.lastMessage = millis();
|
||||||
gpsData.errors = 0;
|
|
||||||
|
|
||||||
portMode_t mode = MODE_RXTX;
|
portMode_t mode = MODE_RXTX;
|
||||||
// only RX is needed for NMEA-style GPS
|
// only RX is needed for NMEA-style GPS
|
||||||
|
@ -227,17 +272,25 @@ void gpsInitUblox(void)
|
||||||
switch (gpsData.state) {
|
switch (gpsData.state) {
|
||||||
case GPS_INITIALIZING:
|
case GPS_INITIALIZING:
|
||||||
now = millis();
|
now = millis();
|
||||||
if (now - gpsData.state_ts < GPS_BAUDRATE_CHATE_DELAY)
|
if (now - gpsData.state_ts < GPS_BAUDRATE_CHANGE_DELAY)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
if (gpsData.state_position < GPS_INIT_ENTRIES) {
|
if (gpsData.state_position < GPS_INIT_ENTRIES) {
|
||||||
// try different speed to INIT
|
// try different speed to INIT
|
||||||
serialSetBaudRate(gpsPort, gpsInitData[gpsData.state_position].baudrate);
|
uint32_t newBaudRate = gpsInitData[gpsData.state_position].baudrate;
|
||||||
// but print our FIXED init string for the baudrate we want to be at
|
|
||||||
|
gpsData.state_ts = now;
|
||||||
|
|
||||||
|
if (serialGetBaudRate(gpsPort) != newBaudRate) {
|
||||||
|
// change the rate if needed and wait a little
|
||||||
|
serialSetBaudRate(gpsPort, newBaudRate);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// print our FIXED init string for the baudrate we want to be at
|
||||||
serialPrint(gpsPort, gpsInitData[gpsData.baudrateIndex].ubx);
|
serialPrint(gpsPort, gpsInitData[gpsData.baudrateIndex].ubx);
|
||||||
|
|
||||||
gpsData.state_position++;
|
gpsData.state_position++;
|
||||||
gpsData.state_ts = now;
|
|
||||||
} else {
|
} else {
|
||||||
// we're now (hopefully) at the correct rate, next state will switch to it
|
// we're now (hopefully) at the correct rate, next state will switch to it
|
||||||
gpsSetState(GPS_CHANGE_BAUD);
|
gpsSetState(GPS_CHANGE_BAUD);
|
||||||
|
@ -248,6 +301,13 @@ void gpsInitUblox(void)
|
||||||
gpsSetState(GPS_CONFIGURE);
|
gpsSetState(GPS_CONFIGURE);
|
||||||
break;
|
break;
|
||||||
case GPS_CONFIGURE:
|
case GPS_CONFIGURE:
|
||||||
|
|
||||||
|
// Either use specific config file for GPS or let dynamically upload config
|
||||||
|
if( gpsConfig->autoConfig == GPS_AUTOCONFIG_OFF ) {
|
||||||
|
gpsSetState(GPS_RECEIVING_DATA);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
if (gpsData.messageState == GPS_MESSAGE_STATE_IDLE) {
|
if (gpsData.messageState == GPS_MESSAGE_STATE_IDLE) {
|
||||||
gpsData.messageState++;
|
gpsData.messageState++;
|
||||||
}
|
}
|
||||||
|
@ -255,10 +315,7 @@ void gpsInitUblox(void)
|
||||||
if (gpsData.messageState == GPS_MESSAGE_STATE_INIT) {
|
if (gpsData.messageState == GPS_MESSAGE_STATE_INIT) {
|
||||||
|
|
||||||
if (gpsData.state_position < sizeof(ubloxInit)) {
|
if (gpsData.state_position < sizeof(ubloxInit)) {
|
||||||
//Either use specific config file for GPS or let dynamically upload config
|
serialWrite(gpsPort, ubloxInit[gpsData.state_position]);
|
||||||
if( gpsConfig->gpsAutoConfig == GPS_AUTOCONFIG_ON ) {
|
|
||||||
serialWrite(gpsPort, ubloxInit[gpsData.state_position]);
|
|
||||||
}
|
|
||||||
gpsData.state_position++;
|
gpsData.state_position++;
|
||||||
} else {
|
} else {
|
||||||
gpsData.state_position = 0;
|
gpsData.state_position = 0;
|
||||||
|
@ -268,10 +325,7 @@ void gpsInitUblox(void)
|
||||||
|
|
||||||
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
||||||
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
||||||
//Either use specific config file for GPS or let dynamically upload config
|
serialWrite(gpsPort, ubloxSbas[gpsConfig->sbasMode].message[gpsData.state_position]);
|
||||||
if( gpsConfig->gpsAutoConfig == GPS_AUTOCONFIG_ON ) {
|
|
||||||
serialWrite(gpsPort, ubloxSbas[gpsConfig->sbasMode].message[gpsData.state_position]);
|
|
||||||
}
|
|
||||||
gpsData.state_position++;
|
gpsData.state_position++;
|
||||||
} else {
|
} else {
|
||||||
gpsData.messageState++;
|
gpsData.messageState++;
|
||||||
|
@ -279,8 +333,8 @@ void gpsInitUblox(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gpsData.messageState >= GPS_MESSAGE_STATE_ENTRY_COUNT) {
|
if (gpsData.messageState >= GPS_MESSAGE_STATE_ENTRY_COUNT) {
|
||||||
|
// ublox should be initialised, try receiving
|
||||||
gpsSetState(GPS_RECEIVING_DATA);
|
gpsSetState(GPS_RECEIVING_DATA);
|
||||||
// ublox should be init'd, time to try receiving
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -297,9 +351,6 @@ void gpsInitHardware(void)
|
||||||
gpsInitUblox();
|
gpsInitUblox();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// clear error counter
|
|
||||||
gpsData.errors = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void gpsThread(void)
|
void gpsThread(void)
|
||||||
|
@ -321,10 +372,12 @@ void gpsThread(void)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case GPS_LOST_COMMUNICATION:
|
case GPS_LOST_COMMUNICATION:
|
||||||
gpsData.errors++;
|
gpsData.timeouts++;
|
||||||
// try another rate
|
if (gpsConfig->autoBaud) {
|
||||||
gpsData.baudrateIndex++;
|
// try another rate
|
||||||
gpsData.baudrateIndex %= GPS_INIT_ENTRIES;
|
gpsData.baudrateIndex++;
|
||||||
|
gpsData.baudrateIndex %= GPS_INIT_ENTRIES;
|
||||||
|
}
|
||||||
gpsData.lastMessage = millis();
|
gpsData.lastMessage = millis();
|
||||||
// TODO - move some / all of these into gpsData
|
// TODO - move some / all of these into gpsData
|
||||||
GPS_numSat = 0;
|
GPS_numSat = 0;
|
||||||
|
@ -380,7 +433,7 @@ bool gpsNewFrame(uint8_t c)
|
||||||
|
|
||||||
|
|
||||||
/* This is a light implementation of a GPS frame decoding
|
/* This is a light implementation of a GPS frame decoding
|
||||||
This should work with most of modern GPS devices configured to output NMEA frames.
|
This should work with most of modern GPS devices configured to output 5 frames.
|
||||||
It assumes there are some NMEA GGA frames to decode on the serial bus
|
It assumes there are some NMEA GGA frames to decode on the serial bus
|
||||||
Now verifies checksum correctly before applying data
|
Now verifies checksum correctly before applying data
|
||||||
|
|
||||||
|
@ -552,10 +605,14 @@ static bool gpsNewFrameNMEA(char c)
|
||||||
case '\r':
|
case '\r':
|
||||||
case '\n':
|
case '\n':
|
||||||
if (checksum_param) { //parity checksum
|
if (checksum_param) { //parity checksum
|
||||||
|
shiftPacketLog();
|
||||||
uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0');
|
uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0');
|
||||||
if (checksum == parity) {
|
if (checksum == parity) {
|
||||||
|
*gpsPacketLogChar = LOG_IGNORED;
|
||||||
|
GPS_packetCount++;
|
||||||
switch (gps_frame) {
|
switch (gps_frame) {
|
||||||
case FRAME_GGA:
|
case FRAME_GGA:
|
||||||
|
*gpsPacketLogChar = LOG_NMEA_GGA;
|
||||||
frameOK = 1;
|
frameOK = 1;
|
||||||
if (STATE(GPS_FIX)) {
|
if (STATE(GPS_FIX)) {
|
||||||
GPS_coord[LAT] = gps_Msg.latitude;
|
GPS_coord[LAT] = gps_Msg.latitude;
|
||||||
|
@ -565,10 +622,13 @@ static bool gpsNewFrameNMEA(char c)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case FRAME_RMC:
|
case FRAME_RMC:
|
||||||
|
*gpsPacketLogChar = LOG_NMEA_RMC;
|
||||||
GPS_speed = gps_Msg.speed;
|
GPS_speed = gps_Msg.speed;
|
||||||
GPS_ground_course = gps_Msg.ground_course;
|
GPS_ground_course = gps_Msg.ground_course;
|
||||||
break;
|
break;
|
||||||
} // end switch
|
} // end switch
|
||||||
|
} else {
|
||||||
|
*gpsPacketLogChar = LOG_ERROR;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
checksum_param = 0;
|
checksum_param = 0;
|
||||||
|
@ -648,7 +708,7 @@ typedef struct {
|
||||||
uint8_t svid; // Satellite ID
|
uint8_t svid; // Satellite ID
|
||||||
uint8_t flags; // Bitmask
|
uint8_t flags; // Bitmask
|
||||||
uint8_t quality; // Bitfield
|
uint8_t quality; // Bitfield
|
||||||
uint8_t cno; // Carrier to Noise Ratio (Signal Strength)
|
uint8_t cno; // Carrier to Noise Ratio (Signal Strength) // dbHz, 0-55.
|
||||||
uint8_t elev; // Elevation in integer degrees
|
uint8_t elev; // Elevation in integer degrees
|
||||||
int16_t azim; // Azimuth in integer degrees
|
int16_t azim; // Azimuth in integer degrees
|
||||||
int32_t prRes; // Pseudo range residual in centimetres
|
int32_t prRes; // Pseudo range residual in centimetres
|
||||||
|
@ -699,6 +759,7 @@ static uint8_t _ck_a;
|
||||||
static uint8_t _ck_b;
|
static uint8_t _ck_b;
|
||||||
|
|
||||||
// State machine state
|
// State machine state
|
||||||
|
static bool _skip_packet;
|
||||||
static uint8_t _step;
|
static uint8_t _step;
|
||||||
static uint8_t _msg_id;
|
static uint8_t _msg_id;
|
||||||
static uint16_t _payload_length;
|
static uint16_t _payload_length;
|
||||||
|
@ -713,6 +774,23 @@ static bool _new_position;
|
||||||
// do we have new speed information?
|
// do we have new speed information?
|
||||||
static bool _new_speed;
|
static bool _new_speed;
|
||||||
|
|
||||||
|
// Example packet sizes from UBlox u-center from a Glonass capable GPS receiver.
|
||||||
|
//15:17:55 R -> UBX NAV-STATUS, Size 24, 'Navigation Status'
|
||||||
|
//15:17:55 R -> UBX NAV-POSLLH, Size 36, 'Geodetic Position'
|
||||||
|
//15:17:55 R -> UBX NAV-VELNED, Size 44, 'Velocity in WGS 84'
|
||||||
|
//15:17:55 R -> UBX NAV-CLOCK, Size 28, 'Clock Status'
|
||||||
|
//15:17:55 R -> UBX NAV-AOPSTATUS, Size 24, 'AOP Status'
|
||||||
|
//15:17:55 R -> UBX 03-09, Size 208, 'Unknown'
|
||||||
|
//15:17:55 R -> UBX 03-10, Size 336, 'Unknown'
|
||||||
|
//15:17:55 R -> UBX NAV-SOL, Size 60, 'Navigation Solution'
|
||||||
|
//15:17:55 R -> UBX NAV, Size 100, 'Navigation'
|
||||||
|
//15:17:55 R -> UBX NAV-SVINFO, Size 328, 'Satellite Status and Information'
|
||||||
|
|
||||||
|
// from the UBlox6 document, the largest payout we receive i the NAV-SVINFO and the payload size
|
||||||
|
// is calculated as 8 + 12*numCh. numCh in the case of a Glonass receiver is 28.
|
||||||
|
#define UBLOX_PAYLOAD_SIZE 344
|
||||||
|
|
||||||
|
|
||||||
// Receive buffer
|
// Receive buffer
|
||||||
static union {
|
static union {
|
||||||
ubx_nav_posllh posllh;
|
ubx_nav_posllh posllh;
|
||||||
|
@ -720,7 +798,7 @@ static union {
|
||||||
ubx_nav_solution solution;
|
ubx_nav_solution solution;
|
||||||
ubx_nav_velned velned;
|
ubx_nav_velned velned;
|
||||||
ubx_nav_svinfo svinfo;
|
ubx_nav_svinfo svinfo;
|
||||||
uint8_t bytes[200];
|
uint8_t bytes[UBLOX_PAYLOAD_SIZE];
|
||||||
} _buffer;
|
} _buffer;
|
||||||
|
|
||||||
void _update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b)
|
void _update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b)
|
||||||
|
@ -735,9 +813,13 @@ void _update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b)
|
||||||
|
|
||||||
static bool UBLOX_parse_gps(void)
|
static bool UBLOX_parse_gps(void)
|
||||||
{
|
{
|
||||||
int i;
|
uint32_t i;
|
||||||
|
|
||||||
|
*gpsPacketLogChar = LOG_IGNORED;
|
||||||
|
|
||||||
switch (_msg_id) {
|
switch (_msg_id) {
|
||||||
case MSG_POSLLH:
|
case MSG_POSLLH:
|
||||||
|
*gpsPacketLogChar = LOG_UBLOX_POSLLH;
|
||||||
//i2c_dataset.time = _buffer.posllh.time;
|
//i2c_dataset.time = _buffer.posllh.time;
|
||||||
GPS_coord[LON] = _buffer.posllh.longitude;
|
GPS_coord[LON] = _buffer.posllh.longitude;
|
||||||
GPS_coord[LAT] = _buffer.posllh.latitude;
|
GPS_coord[LAT] = _buffer.posllh.latitude;
|
||||||
|
@ -750,11 +832,13 @@ static bool UBLOX_parse_gps(void)
|
||||||
_new_position = true;
|
_new_position = true;
|
||||||
break;
|
break;
|
||||||
case MSG_STATUS:
|
case MSG_STATUS:
|
||||||
|
*gpsPacketLogChar = LOG_UBLOX_STATUS;
|
||||||
next_fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D);
|
next_fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D);
|
||||||
if (!next_fix)
|
if (!next_fix)
|
||||||
DISABLE_STATE(GPS_FIX);
|
DISABLE_STATE(GPS_FIX);
|
||||||
break;
|
break;
|
||||||
case MSG_SOL:
|
case MSG_SOL:
|
||||||
|
*gpsPacketLogChar = LOG_UBLOX_SOL;
|
||||||
next_fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
|
next_fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
|
||||||
if (!next_fix)
|
if (!next_fix)
|
||||||
DISABLE_STATE(GPS_FIX);
|
DISABLE_STATE(GPS_FIX);
|
||||||
|
@ -762,12 +846,14 @@ static bool UBLOX_parse_gps(void)
|
||||||
GPS_hdop = _buffer.solution.position_DOP;
|
GPS_hdop = _buffer.solution.position_DOP;
|
||||||
break;
|
break;
|
||||||
case MSG_VELNED:
|
case MSG_VELNED:
|
||||||
|
*gpsPacketLogChar = LOG_UBLOX_VELNED;
|
||||||
// speed_3d = _buffer.velned.speed_3d; // cm/s
|
// speed_3d = _buffer.velned.speed_3d; // cm/s
|
||||||
GPS_speed = _buffer.velned.speed_2d; // cm/s
|
GPS_speed = _buffer.velned.speed_2d; // cm/s
|
||||||
GPS_ground_course = (uint16_t) (_buffer.velned.heading_2d / 10000); // Heading 2D deg * 100000 rescaled to deg * 10
|
GPS_ground_course = (uint16_t) (_buffer.velned.heading_2d / 10000); // Heading 2D deg * 100000 rescaled to deg * 10
|
||||||
_new_speed = true;
|
_new_speed = true;
|
||||||
break;
|
break;
|
||||||
case MSG_SVINFO:
|
case MSG_SVINFO:
|
||||||
|
*gpsPacketLogChar = LOG_UBLOX_SVINFO;
|
||||||
GPS_numCh = _buffer.svinfo.numCh;
|
GPS_numCh = _buffer.svinfo.numCh;
|
||||||
if (GPS_numCh > 16)
|
if (GPS_numCh > 16)
|
||||||
GPS_numCh = 16;
|
GPS_numCh = 16;
|
||||||
|
@ -796,69 +882,89 @@ static bool gpsNewFrameUBLOX(uint8_t data)
|
||||||
bool parsed = false;
|
bool parsed = false;
|
||||||
|
|
||||||
switch (_step) {
|
switch (_step) {
|
||||||
case 1:
|
case 0: // Sync char 1 (0xB5)
|
||||||
if (PREAMBLE2 == data) {
|
if (PREAMBLE1 == data) {
|
||||||
|
_skip_packet = false;
|
||||||
_step++;
|
_step++;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 1: // Sync char 2 (0x62)
|
||||||
|
if (PREAMBLE2 != data) {
|
||||||
|
_step = 0;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
_step = 0;
|
_step++;
|
||||||
case 0:
|
|
||||||
if (PREAMBLE1 == data)
|
|
||||||
_step++;
|
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2: // Class
|
||||||
_step++;
|
_step++;
|
||||||
_class = data;
|
_class = data;
|
||||||
_ck_b = _ck_a = data; // reset the checksum accumulators
|
_ck_b = _ck_a = data; // reset the checksum accumulators
|
||||||
break;
|
break;
|
||||||
case 3:
|
case 3: // Id
|
||||||
_step++;
|
_step++;
|
||||||
_ck_b += (_ck_a += data); // checksum byte
|
_ck_b += (_ck_a += data); // checksum byte
|
||||||
_msg_id = data;
|
_msg_id = data;
|
||||||
break;
|
break;
|
||||||
case 4:
|
case 4: // Payload length (part 1)
|
||||||
_step++;
|
_step++;
|
||||||
_ck_b += (_ck_a += data); // checksum byte
|
_ck_b += (_ck_a += data); // checksum byte
|
||||||
_payload_length = data; // payload length low byte
|
_payload_length = data; // payload length low byte
|
||||||
break;
|
break;
|
||||||
case 5:
|
case 5: // Payload length (part 2)
|
||||||
_step++;
|
_step++;
|
||||||
_ck_b += (_ck_a += data); // checksum byte
|
_ck_b += (_ck_a += data); // checksum byte
|
||||||
_payload_length += (uint16_t)(data << 8);
|
_payload_length += (uint16_t)(data << 8);
|
||||||
if (_payload_length > 512) {
|
if (_payload_length > UBLOX_PAYLOAD_SIZE) {
|
||||||
_payload_length = 0;
|
_skip_packet = true;
|
||||||
_step = 0;
|
|
||||||
}
|
}
|
||||||
_payload_counter = 0; // prepare to receive payload
|
_payload_counter = 0; // prepare to receive payload
|
||||||
|
if (_payload_length == 0) {
|
||||||
|
_step = 7;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 6:
|
case 6:
|
||||||
_ck_b += (_ck_a += data); // checksum byte
|
_ck_b += (_ck_a += data); // checksum byte
|
||||||
if (_payload_counter < sizeof(_buffer)) {
|
if (_payload_counter < UBLOX_PAYLOAD_SIZE) {
|
||||||
_buffer.bytes[_payload_counter] = data;
|
_buffer.bytes[_payload_counter] = data;
|
||||||
}
|
}
|
||||||
if (++_payload_counter == _payload_length)
|
if (++_payload_counter >= _payload_length) {
|
||||||
_step++;
|
_step++;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 7:
|
case 7:
|
||||||
_step++;
|
_step++;
|
||||||
if (_ck_a != data)
|
if (_ck_a != data) {
|
||||||
_step = 0; // bad checksum
|
_skip_packet = true; // bad checksum
|
||||||
|
gpsData.errors++;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 8:
|
case 8:
|
||||||
_step = 0;
|
_step = 0;
|
||||||
if (_ck_b != data)
|
|
||||||
|
shiftPacketLog();
|
||||||
|
|
||||||
|
if (_ck_b != data) {
|
||||||
|
*gpsPacketLogChar = LOG_ERROR;
|
||||||
|
gpsData.errors++;
|
||||||
break; // bad checksum
|
break; // bad checksum
|
||||||
if (UBLOX_parse_gps())
|
}
|
||||||
|
|
||||||
|
GPS_packetCount++;
|
||||||
|
|
||||||
|
if (_skip_packet) {
|
||||||
|
*gpsPacketLogChar = LOG_SKIPPED;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (UBLOX_parse_gps()) {
|
||||||
parsed = true;
|
parsed = true;
|
||||||
} //end switch
|
}
|
||||||
|
}
|
||||||
return parsed;
|
return parsed;
|
||||||
}
|
}
|
||||||
|
|
||||||
gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
||||||
{
|
{
|
||||||
if (gpsData.state != GPS_RECEIVING_DATA)
|
|
||||||
return GPS_PASSTHROUGH_NO_GPS;
|
|
||||||
|
|
||||||
serialPort_t *gpsPassthroughPort = findOpenSerialPort(FUNCTION_GPS_PASSTHROUGH);
|
serialPort_t *gpsPassthroughPort = findOpenSerialPort(FUNCTION_GPS_PASSTHROUGH);
|
||||||
if (gpsPassthroughPort) {
|
if (gpsPassthroughPort) {
|
||||||
|
|
||||||
|
@ -870,16 +976,25 @@ gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
||||||
return GPS_PASSTHROUGH_NO_SERIAL_PORT;
|
return GPS_PASSTHROUGH_NO_SERIAL_PORT;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
serialSetBaudRate(gpsPort, serialConfig->gps_baudrate);
|
||||||
if(!(gpsPort->mode & MODE_TX))
|
if(!(gpsPort->mode & MODE_TX))
|
||||||
serialSetMode(gpsPort, gpsPort->mode | MODE_TX);
|
serialSetMode(gpsPort, gpsPort->mode | MODE_TX);
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
|
||||||
|
#ifdef DISPLAY
|
||||||
|
if (feature(FEATURE_DISPLAY)) {
|
||||||
|
displayShowFixedPage(PAGE_GPS);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
char c;
|
||||||
while(1) {
|
while(1) {
|
||||||
if (serialTotalBytesWaiting(gpsPort)) {
|
if (serialTotalBytesWaiting(gpsPort)) {
|
||||||
LED0_ON;
|
LED0_ON;
|
||||||
serialWrite(gpsPassthroughPort, serialRead(gpsPort));
|
c = serialRead(gpsPort);
|
||||||
|
gpsNewData(c);
|
||||||
|
serialWrite(gpsPassthroughPort, c);
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
}
|
}
|
||||||
if (serialTotalBytesWaiting(gpsPassthroughPort)) {
|
if (serialTotalBytesWaiting(gpsPassthroughPort)) {
|
||||||
|
@ -887,6 +1002,12 @@ gpsEnablePassthroughResult_e gpsEnablePassthrough(void)
|
||||||
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
|
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
}
|
}
|
||||||
|
#ifdef DISPLAY
|
||||||
|
if (feature(FEATURE_DISPLAY)) {
|
||||||
|
updateDisplay();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
return GPS_PASSTHROUGH_ENABLED;
|
return GPS_PASSTHROUGH_ENABLED;
|
||||||
}
|
}
|
||||||
|
|
|
@ -48,20 +48,26 @@ typedef enum {
|
||||||
} gpsBaudRate_e;
|
} gpsBaudRate_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_AUTOCONFIG_ON = 0,
|
GPS_AUTOCONFIG_OFF = 0,
|
||||||
GPS_AUTOCONFIG_OFF
|
GPS_AUTOCONFIG_ON,
|
||||||
} gpsAutoConfig_e;
|
} gpsAutoConfig_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
GPS_AUTOBAUD_OFF = 0,
|
||||||
|
GPS_AUTOBAUD_ON
|
||||||
|
} gpsAutoBaud_e;
|
||||||
|
|
||||||
#define GPS_BAUDRATE_MAX GPS_BAUDRATE_9600
|
#define GPS_BAUDRATE_MAX GPS_BAUDRATE_9600
|
||||||
|
|
||||||
typedef struct gpsConfig_s {
|
typedef struct gpsConfig_s {
|
||||||
gpsProvider_e provider;
|
gpsProvider_e provider;
|
||||||
sbasMode_e sbasMode;
|
sbasMode_e sbasMode;
|
||||||
gpsAutoConfig_e gpsAutoConfig;
|
gpsAutoConfig_e autoConfig;
|
||||||
|
gpsAutoBaud_e autoBaud;
|
||||||
} gpsConfig_t;
|
} gpsConfig_t;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_PASSTHROUGH_ENABLED = 1,
|
GPS_PASSTHROUGH_ENABLED = 1,
|
||||||
GPS_PASSTHROUGH_NO_GPS,
|
|
||||||
GPS_PASSTHROUGH_NO_SERIAL_PORT
|
GPS_PASSTHROUGH_NO_SERIAL_PORT
|
||||||
} gpsEnablePassthroughResult_e;
|
} gpsEnablePassthroughResult_e;
|
||||||
|
|
||||||
|
@ -83,7 +89,8 @@ typedef enum {
|
||||||
typedef struct gpsData_t {
|
typedef struct gpsData_t {
|
||||||
uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
|
uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
|
||||||
uint8_t baudrateIndex; // index into auto-detecting or current baudrate
|
uint8_t baudrateIndex; // index into auto-detecting or current baudrate
|
||||||
int errors; // gps error counter - crc error/lost of data/sync etc. reset on each reinit.
|
uint32_t errors; // gps error counter - crc error/lost of data/sync etc..
|
||||||
|
uint32_t timeouts;
|
||||||
uint32_t lastMessage; // last time valid GPS data was received (millis)
|
uint32_t lastMessage; // last time valid GPS data was received (millis)
|
||||||
uint32_t lastLastMessage; // last-last valid GPS message. Used to calculate delta.
|
uint32_t lastLastMessage; // last-last valid GPS message. Used to calculate delta.
|
||||||
|
|
||||||
|
@ -92,13 +99,16 @@ typedef struct gpsData_t {
|
||||||
gpsMessageState_e messageState;
|
gpsMessageState_e messageState;
|
||||||
} gpsData_t;
|
} gpsData_t;
|
||||||
|
|
||||||
|
#define GPS_PACKET_LOG_ENTRY_COUNT 21 // To make this useful we should log as many packets as we can fit characters a single line of a OLED display.
|
||||||
|
extern char gpsPacketLog[GPS_PACKET_LOG_ENTRY_COUNT];
|
||||||
|
|
||||||
extern gpsData_t gpsData;
|
extern gpsData_t gpsData;
|
||||||
extern int32_t GPS_coord[2]; // LAT/LON
|
extern int32_t GPS_coord[2]; // LAT/LON
|
||||||
|
|
||||||
extern uint8_t GPS_numSat;
|
extern uint8_t GPS_numSat;
|
||||||
extern uint16_t GPS_hdop; // GPS signal quality
|
extern uint16_t GPS_hdop; // GPS signal quality
|
||||||
extern uint8_t GPS_update; // it's a binary toogle to distinct a GPS position update
|
extern uint8_t GPS_update; // it's a binary toogle to distinct a GPS position update
|
||||||
|
extern uint32_t GPS_packetCount;
|
||||||
extern uint16_t GPS_altitude; // altitude in 0.1m
|
extern uint16_t GPS_altitude; // altitude in 0.1m
|
||||||
extern uint16_t GPS_speed; // speed in 0.1m/s
|
extern uint16_t GPS_speed; // speed in 0.1m/s
|
||||||
extern uint16_t GPS_ground_course; // degrees * 10
|
extern uint16_t GPS_ground_course; // degrees * 10
|
||||||
|
@ -108,6 +118,10 @@ extern uint8_t GPS_svinfo_svid[16]; // Satellite ID
|
||||||
extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
||||||
extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
||||||
|
|
||||||
|
#define GPS_DBHZ_MIN 0
|
||||||
|
#define GPS_DBHZ_MAX 55
|
||||||
|
|
||||||
|
|
||||||
void gpsThread(void);
|
void gpsThread(void);
|
||||||
bool gpsNewFrame(uint8_t c);
|
bool gpsNewFrame(uint8_t c);
|
||||||
gpsEnablePassthroughResult_e gpsEnablePassthrough(void);
|
gpsEnablePassthroughResult_e gpsEnablePassthrough(void);
|
||||||
|
|
|
@ -78,8 +78,10 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||||
#if (SERIAL_PORT_COUNT > 3)
|
#if (SERIAL_PORT_COUNT > 3)
|
||||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||||
|
#if (SERIAL_PORT_COUNT > 4)
|
||||||
{SERIAL_PORT_USART4, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
{SERIAL_PORT_USART4, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
|
@ -87,8 +89,10 @@ static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
#if (SERIAL_PORT_COUNT > 3)
|
#if (SERIAL_PORT_COUNT > 3)
|
||||||
{SERIAL_PORT_USART3, 9600, 19200, SPF_SUPPORTS_CALLBACK},
|
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART4, 9600, 19200, SPF_SUPPORTS_CALLBACK}
|
#if (SERIAL_PORT_COUNT > 4)
|
||||||
|
{SERIAL_PORT_USART4, 9600, 115200, SPF_SUPPORTS_CALLBACK}
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
|
#include "rx/spektrum.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
@ -133,7 +134,7 @@ static const char * const sensorNames[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char * const accNames[] = {
|
static const char * const accNames[] = {
|
||||||
"", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", "None", NULL
|
"", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9150", "FAKE", "None", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
@ -251,7 +252,8 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
{ "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
||||||
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
||||||
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.gpsAutoConfig, 0, GPS_AUTOCONFIG_OFF },
|
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoConfig, GPS_AUTOCONFIG_OFF, GPS_AUTOCONFIG_ON },
|
||||||
|
{ "gps_auto_baud", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoBaud, GPS_AUTOBAUD_OFF, GPS_AUTOBAUD_ON },
|
||||||
|
|
||||||
|
|
||||||
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 },
|
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 },
|
||||||
|
@ -271,6 +273,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||||
|
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX},
|
||||||
|
|
||||||
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||||
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
||||||
|
@ -952,10 +955,6 @@ static void cliGpsPassthrough(char *cmdline)
|
||||||
gpsEnablePassthroughResult_e result = gpsEnablePassthrough();
|
gpsEnablePassthroughResult_e result = gpsEnablePassthrough();
|
||||||
|
|
||||||
switch (result) {
|
switch (result) {
|
||||||
case GPS_PASSTHROUGH_NO_GPS:
|
|
||||||
cliPrint("Error: Enable and plug in GPS first\r\n");
|
|
||||||
break;
|
|
||||||
|
|
||||||
case GPS_PASSTHROUGH_NO_SERIAL_PORT:
|
case GPS_PASSTHROUGH_NO_SERIAL_PORT:
|
||||||
cliPrint("Error: Enable and plug in GPS first\r\n");
|
cliPrint("Error: Enable and plug in GPS first\r\n");
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -1016,6 +1016,8 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize16(masterConfig.rxConfig.maxcheck);
|
serialize16(masterConfig.rxConfig.maxcheck);
|
||||||
serialize16(masterConfig.rxConfig.midrc);
|
serialize16(masterConfig.rxConfig.midrc);
|
||||||
serialize16(masterConfig.rxConfig.mincheck);
|
serialize16(masterConfig.rxConfig.mincheck);
|
||||||
|
serialize8(masterConfig.rxConfig.spektrum_sat_bind);
|
||||||
|
break;
|
||||||
|
|
||||||
case MSP_RSSI_CONFIG:
|
case MSP_RSSI_CONFIG:
|
||||||
headSerialReply(1);
|
headSerialReply(1);
|
||||||
|
@ -1291,6 +1293,7 @@ static bool processInCommand(void)
|
||||||
masterConfig.rxConfig.maxcheck = read16();
|
masterConfig.rxConfig.maxcheck = read16();
|
||||||
masterConfig.rxConfig.midrc = read16();
|
masterConfig.rxConfig.midrc = read16();
|
||||||
masterConfig.rxConfig.mincheck = read16();
|
masterConfig.rxConfig.mincheck = read16();
|
||||||
|
masterConfig.rxConfig.spektrum_sat_bind = read8();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_RSSI_CONFIG:
|
case MSP_SET_RSSI_CONFIG:
|
||||||
|
|
|
@ -106,7 +106,7 @@ void imuInit(void);
|
||||||
void displayInit(rxConfig_t *intialRxConfig);
|
void displayInit(rxConfig_t *intialRxConfig);
|
||||||
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, failsafe_t* failsafeToUse);
|
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, failsafe_t* failsafeToUse);
|
||||||
void loop(void);
|
void loop(void);
|
||||||
|
void spektrumBind(rxConfig_t *rxConfig);
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
#ifdef STM32F303xC
|
||||||
// from system_stm32f30x.c
|
// from system_stm32f30x.c
|
||||||
|
@ -151,6 +151,20 @@ void init(void)
|
||||||
|
|
||||||
systemInit();
|
systemInit();
|
||||||
|
|
||||||
|
#ifdef SPEKTRUM_BIND
|
||||||
|
if (feature(FEATURE_RX_SERIAL)) {
|
||||||
|
switch (masterConfig.rxConfig.serialrx_provider) {
|
||||||
|
case SERIALRX_SPEKTRUM1024:
|
||||||
|
case SERIALRX_SPEKTRUM2048:
|
||||||
|
// Spektrum satellite binding if enabled on startup.
|
||||||
|
// Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
|
||||||
|
// The rest of Spektrum initialization will happen later - via spektrumInit()
|
||||||
|
spektrumBind(&masterConfig.rxConfig);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
delay(100);
|
delay(100);
|
||||||
|
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
@ -201,6 +215,7 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(SPARKY)
|
||||||
adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
|
adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
|
||||||
adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER);
|
adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER);
|
||||||
adc_params.enableExternal1 = false;
|
adc_params.enableExternal1 = false;
|
||||||
|
@ -213,6 +228,8 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
adcInit(&adc_params);
|
adcInit(&adc_params);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
initBoardAlignment(&masterConfig.boardAlignment);
|
initBoardAlignment(&masterConfig.boardAlignment);
|
||||||
|
|
||||||
|
@ -362,7 +379,11 @@ void init(void)
|
||||||
|
|
||||||
#ifdef DISPLAY
|
#ifdef DISPLAY
|
||||||
if (feature(FEATURE_DISPLAY)) {
|
if (feature(FEATURE_DISPLAY)) {
|
||||||
|
#ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY
|
||||||
|
displayShowFixedPage(PAGE_GPS);
|
||||||
|
#else
|
||||||
displayEnablePageCycling();
|
displayEnablePageCycling();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -420,7 +420,6 @@ typedef enum {
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(BARO) || defined(SONAR)
|
||||||
CALCULATE_ALTITUDE_TASK,
|
CALCULATE_ALTITUDE_TASK,
|
||||||
#endif
|
#endif
|
||||||
UPDATE_GPS_TASK,
|
|
||||||
UPDATE_DISPLAY_TASK
|
UPDATE_DISPLAY_TASK
|
||||||
} periodicTasks;
|
} periodicTasks;
|
||||||
|
|
||||||
|
@ -464,17 +463,6 @@ void executePeriodicTasks(void)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
|
||||||
case UPDATE_GPS_TASK:
|
|
||||||
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
|
|
||||||
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
|
|
||||||
// change this based on available hardware
|
|
||||||
if (feature(FEATURE_GPS)) {
|
|
||||||
gpsThread();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
#ifdef SONAR
|
#ifdef SONAR
|
||||||
case UPDATE_SONAR_TASK:
|
case UPDATE_SONAR_TASK:
|
||||||
if (sensors(SENSOR_SONAR)) {
|
if (sensors(SENSOR_SONAR)) {
|
||||||
|
@ -642,6 +630,15 @@ void loop(void)
|
||||||
} else {
|
} else {
|
||||||
// not processing rx this iteration
|
// not processing rx this iteration
|
||||||
executePeriodicTasks();
|
executePeriodicTasks();
|
||||||
|
|
||||||
|
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
|
||||||
|
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
|
||||||
|
// change this based on available hardware
|
||||||
|
#ifdef GPS
|
||||||
|
if (feature(FEATURE_GPS)) {
|
||||||
|
gpsThread();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
currentTime = micros();
|
currentTime = micros();
|
||||||
|
|
|
@ -65,6 +65,7 @@ extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2
|
||||||
typedef struct rxConfig_s {
|
typedef struct rxConfig_s {
|
||||||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
||||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||||
|
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||||
uint16_t mincheck; // minimum rc end
|
uint16_t mincheck; // minimum rc end
|
||||||
uint16_t maxcheck; // maximum rc end
|
uint16_t maxcheck; // maximum rc end
|
||||||
|
|
|
@ -21,12 +21,15 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/gpio.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/spektrum.h"
|
#include "rx/spektrum.h"
|
||||||
|
|
||||||
|
@ -138,3 +141,78 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
|
||||||
|
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef SPEKTRUM_BIND
|
||||||
|
|
||||||
|
bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||||
|
{
|
||||||
|
#ifdef HARDWARE_BIND_PLUG
|
||||||
|
gpio_config_t cfg = {
|
||||||
|
BINDPLUG_PIN,
|
||||||
|
Mode_IPU,
|
||||||
|
Speed_2MHz
|
||||||
|
};
|
||||||
|
gpioInit(BINDPLUG_PORT, &cfg);
|
||||||
|
|
||||||
|
// Check status of bind plug and exit if not active
|
||||||
|
delayMicroseconds(10); // allow configuration to settle
|
||||||
|
if (digitalIn(BINDPLUG_PORT, BINDPLUG_PIN)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return !(
|
||||||
|
isMPUSoftReset() ||
|
||||||
|
spektrum_sat_bind == SPEKTRUM_SAT_BIND_DISABLED ||
|
||||||
|
spektrum_sat_bind > SPEKTRUM_SAT_BIND_MAX
|
||||||
|
);
|
||||||
|
}
|
||||||
|
/* spektrumBind function ported from Baseflight. It's used to bind satellite receiver to TX.
|
||||||
|
* Function must be called immediately after startup so that we don't miss satellite bind window.
|
||||||
|
* Known parameters. Tested with DSMX satellite and DX8 radio. Framerate (11ms or 22ms) must be selected from TX.
|
||||||
|
* 9 = DSMX 11ms / DSMX 22ms
|
||||||
|
* 5 = DSM2 11ms 2048 / DSM2 22ms 1024
|
||||||
|
*/
|
||||||
|
void spektrumBind(rxConfig_t *rxConfig)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
|
||||||
|
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
gpio_config_t cfg = {
|
||||||
|
BIND_PIN,
|
||||||
|
Mode_Out_OD,
|
||||||
|
Speed_2MHz
|
||||||
|
};
|
||||||
|
gpioInit(BIND_PORT, &cfg);
|
||||||
|
|
||||||
|
// RX line, set high
|
||||||
|
digitalHi(BIND_PORT, BIND_PIN);
|
||||||
|
|
||||||
|
// Bind window is around 20-140ms after powerup
|
||||||
|
delay(60);
|
||||||
|
|
||||||
|
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
|
||||||
|
|
||||||
|
// RX line, drive low for 120us
|
||||||
|
digitalLo(BIND_PORT, BIND_PIN);
|
||||||
|
delayMicroseconds(120);
|
||||||
|
|
||||||
|
// RX line, drive high for 120us
|
||||||
|
digitalHi(BIND_PORT, BIND_PIN);
|
||||||
|
delayMicroseconds(120);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef HARDWARE_BIND_PLUG
|
||||||
|
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
||||||
|
// Don't reset if hardware bind plug is present
|
||||||
|
if (!isMPUSoftReset()) {
|
||||||
|
rxConfig->spektrum_sat_bind = 0;
|
||||||
|
saveConfigAndNotify();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -17,5 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#define SPEKTRUM_SAT_BIND_DISABLED 0
|
||||||
|
#define SPEKTRUM_SAT_BIND_MAX 10
|
||||||
|
|
||||||
bool spektrumFrameComplete(void);
|
bool spektrumFrameComplete(void);
|
||||||
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
void spektrumUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint);
|
||||||
|
|
|
@ -27,8 +27,9 @@ typedef enum AccelSensors {
|
||||||
ACC_LSM303DLHC = 5,
|
ACC_LSM303DLHC = 5,
|
||||||
ACC_SPI_MPU6000 = 6,
|
ACC_SPI_MPU6000 = 6,
|
||||||
ACC_SPI_MPU6500 = 7,
|
ACC_SPI_MPU6500 = 7,
|
||||||
ACC_FAKE = 8,
|
ACC_MPU9150 = 8,
|
||||||
ACC_NONE = 9
|
ACC_FAKE = 9,
|
||||||
|
ACC_NONE = 10
|
||||||
} AccelSensors;
|
} AccelSensors;
|
||||||
|
|
||||||
extern uint8_t accHardware;
|
extern uint8_t accHardware;
|
||||||
|
|
|
@ -109,6 +109,8 @@ static void applyGyroZero(void)
|
||||||
|
|
||||||
void gyroGetADC(void)
|
void gyroGetADC(void)
|
||||||
{
|
{
|
||||||
|
// FIXME When gyro.read() fails due to i2c or other error gyroZero is continually re-applied to gyroADC resulting in a old reading that gets worse over time.
|
||||||
|
|
||||||
// range: +/- 8192; +/- 2000 deg/sec
|
// range: +/- 8192; +/- 2000 deg/sec
|
||||||
gyro.read(gyroADC);
|
gyro.read(gyroADC);
|
||||||
alignSensors(gyroADC, gyroADC, gyroAlign);
|
alignSensors(gyroADC, gyroADC, gyroAlign);
|
||||||
|
|
|
@ -32,6 +32,7 @@
|
||||||
#include "drivers/accgyro_mma845x.h"
|
#include "drivers/accgyro_mma845x.h"
|
||||||
#include "drivers/accgyro_mpu3050.h"
|
#include "drivers/accgyro_mpu3050.h"
|
||||||
#include "drivers/accgyro_mpu6050.h"
|
#include "drivers/accgyro_mpu6050.h"
|
||||||
|
#include "drivers/accgyro_mpu9150.h"
|
||||||
|
|
||||||
#include "drivers/accgyro_l3gd20.h"
|
#include "drivers/accgyro_l3gd20.h"
|
||||||
#include "drivers/accgyro_lsm303dlhc.h"
|
#include "drivers/accgyro_lsm303dlhc.h"
|
||||||
|
@ -139,6 +140,12 @@ bool detectGyro(uint16_t gyroLpf)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_GYRO_MPU9150
|
||||||
|
if (mpu9150GyroDetect(NULL, &gyro, gyroLpf)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_L3G4200D
|
#ifdef USE_GYRO_L3G4200D
|
||||||
if (l3g4200dDetect(&gyro, gyroLpf)) {
|
if (l3g4200dDetect(&gyro, gyroLpf)) {
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
|
@ -245,6 +252,15 @@ retry:
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef USE_ACC_MPU9150
|
||||||
|
case ACC_MPU9150: // MPU9150
|
||||||
|
if (mpu9150AccDetect(NULL, &acc)) {
|
||||||
|
accHardware = ACC_MPU9150;
|
||||||
|
if (accHardwareToUse == ACC_MPU9150)
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
; // fallthrough
|
||||||
|
#endif
|
||||||
#ifdef USE_ACC_MMA8452
|
#ifdef USE_ACC_MMA8452
|
||||||
case ACC_MMA8452: // MMA8452
|
case ACC_MMA8452: // MMA8452
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
|
|
|
@ -76,3 +76,8 @@
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART3, PB11 (Flexport)
|
||||||
|
#define BIND_PORT GPIOB
|
||||||
|
#define BIND_PIN Pin_11
|
||||||
|
|
|
@ -55,9 +55,9 @@
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* APB1 Prescaler | 2
|
* APB1 Prescaler | 2
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* HSE Frequency(Hz) | 12000000
|
* HSE Frequency(Hz) | 8000000
|
||||||
*----------------------------------------------------------------------------
|
*----------------------------------------------------------------------------
|
||||||
* PLLMUL | 6
|
* PLLMUL | 9
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* PREDIV | 1
|
* PREDIV | 1
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
|
|
|
@ -61,3 +61,8 @@
|
||||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)
|
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)
|
||||||
|
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART2, PA3
|
||||||
|
#define BIND_PORT GPIOA
|
||||||
|
#define BIND_PIN Pin_3
|
||||||
|
|
|
@ -99,3 +99,7 @@
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART2, PA3
|
||||||
|
#define BIND_PORT GPIOA
|
||||||
|
#define BIND_PIN Pin_3
|
||||||
|
|
|
@ -113,3 +113,8 @@
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART2, PA3
|
||||||
|
#define BIND_PORT GPIOA
|
||||||
|
#define BIND_PIN Pin_3
|
||||||
|
|
|
@ -47,3 +47,8 @@
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART2, PA3
|
||||||
|
#define BIND_PORT GPIOA
|
||||||
|
#define BIND_PIN Pin_3
|
||||||
|
|
372
src/main/target/SPARKY/system_stm32f30x.c
Normal file
|
@ -0,0 +1,372 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file system_stm32f30x.c
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V1.1.1
|
||||||
|
* @date 28-March-2014
|
||||||
|
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||||
|
* This file contains the system clock configuration for STM32F30x devices,
|
||||||
|
* and is generated by the clock configuration tool
|
||||||
|
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||||
|
*
|
||||||
|
* 1. This file provides two functions and one global variable to be called from
|
||||||
|
* user application:
|
||||||
|
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||||
|
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||||
|
* depending on the configuration made in the clock xls tool.
|
||||||
|
* This function is called at startup just after reset and
|
||||||
|
* before branch to main program. This call is made inside
|
||||||
|
* the "startup_stm32f30x.s" file.
|
||||||
|
*
|
||||||
|
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||||
|
* by the user application to setup the SysTick
|
||||||
|
* timer or configure other parameters.
|
||||||
|
*
|
||||||
|
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||||
|
* be called whenever the core clock is changed
|
||||||
|
* during program execution.
|
||||||
|
*
|
||||||
|
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||||
|
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||||
|
* configure the system clock before to branch to main program.
|
||||||
|
*
|
||||||
|
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||||
|
* function will do nothing and HSI still used as system clock source. User can
|
||||||
|
* add some code to deal with this issue inside the SetSysClock() function.
|
||||||
|
*
|
||||||
|
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||||
|
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||||
|
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||||
|
* value to your own configuration.
|
||||||
|
*
|
||||||
|
* 5. This file configures the system clock as follows:
|
||||||
|
*=============================================================================
|
||||||
|
* Supported STM32F30x device
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* System Clock source | PLL (HSE)
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* SYSCLK(Hz) | 72000000
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* HCLK(Hz) | 72000000
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* AHB Prescaler | 1
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* APB2 Prescaler | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* APB1 Prescaler | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* HSE Frequency(Hz) | 8000000
|
||||||
|
*----------------------------------------------------------------------------
|
||||||
|
* PLLMUL | 9
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* PREDIV | 1
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* USB Clock | ENABLE
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Flash Latency(WS) | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Prefetch Buffer | ON
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
*=============================================================================
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||||
|
* You may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at:
|
||||||
|
*
|
||||||
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/** @addtogroup CMSIS
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Includes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "stm32f30x.h"
|
||||||
|
|
||||||
|
uint32_t hse_value = HSE_VALUE;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||||
|
Internal SRAM. */
|
||||||
|
/* #define VECT_TAB_SRAM */
|
||||||
|
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||||
|
This value must be a multiple of 0x200. */
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private macro -------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Variables
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint32_t SystemCoreClock = 72000000;
|
||||||
|
|
||||||
|
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
void SetSysClock(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Setup the microcontroller system
|
||||||
|
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||||
|
* SystemFrequency variable.
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SystemInit(void)
|
||||||
|
{
|
||||||
|
/* FPU settings ------------------------------------------------------------*/
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||||
|
/* Set HSION bit */
|
||||||
|
RCC->CR |= (uint32_t)0x00000001;
|
||||||
|
|
||||||
|
/* Reset CFGR register */
|
||||||
|
RCC->CFGR &= 0xF87FC00C;
|
||||||
|
|
||||||
|
/* Reset HSEON, CSSON and PLLON bits */
|
||||||
|
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||||
|
|
||||||
|
/* Reset HSEBYP bit */
|
||||||
|
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||||
|
|
||||||
|
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||||
|
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||||
|
|
||||||
|
/* Reset PREDIV1[3:0] bits */
|
||||||
|
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||||
|
|
||||||
|
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||||
|
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||||
|
|
||||||
|
/* Disable all interrupts */
|
||||||
|
RCC->CIR = 0x00000000;
|
||||||
|
|
||||||
|
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||||
|
//SetSysClock(); // called from main()
|
||||||
|
|
||||||
|
#ifdef VECT_TAB_SRAM
|
||||||
|
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||||
|
#else
|
||||||
|
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||||
|
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||||
|
* be used by the user application to setup the SysTick timer or configure
|
||||||
|
* other parameters.
|
||||||
|
*
|
||||||
|
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||||
|
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||||
|
* based on this variable will be incorrect.
|
||||||
|
*
|
||||||
|
* @note - The system frequency computed by this function is not the real
|
||||||
|
* frequency in the chip. It is calculated based on the predefined
|
||||||
|
* constant and the selected clock source:
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||||
|
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||||
|
*
|
||||||
|
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||||
|
* 8 MHz) but the real value may vary depending on the variations
|
||||||
|
* in voltage and temperature.
|
||||||
|
*
|
||||||
|
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||||
|
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||||
|
* frequency of the crystal used. Otherwise, this function may
|
||||||
|
* have wrong result.
|
||||||
|
*
|
||||||
|
* - The result of this function could be not correct when using fractional
|
||||||
|
* value for HSE crystal.
|
||||||
|
*
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SystemCoreClockUpdate (void)
|
||||||
|
{
|
||||||
|
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||||
|
|
||||||
|
/* Get SYSCLK source -------------------------------------------------------*/
|
||||||
|
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||||
|
|
||||||
|
switch (tmp)
|
||||||
|
{
|
||||||
|
case 0x00: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x04: /* HSE used as system clock */
|
||||||
|
SystemCoreClock = HSE_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x08: /* PLL used as system clock */
|
||||||
|
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||||
|
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||||
|
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||||
|
pllmull = ( pllmull >> 18) + 2;
|
||||||
|
|
||||||
|
if (pllsource == 0x00)
|
||||||
|
{
|
||||||
|
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||||
|
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||||
|
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||||
|
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/* Compute HCLK clock frequency ----------------*/
|
||||||
|
/* Get HCLK prescaler */
|
||||||
|
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||||
|
/* HCLK clock frequency */
|
||||||
|
SystemCoreClock >>= tmp;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
* AHB/APBx prescalers and Flash settings
|
||||||
|
* @note This function should be called only once the RCC clock configuration
|
||||||
|
* is reset to the default reset state (done in SystemInit() function).
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SetSysClock(void)
|
||||||
|
{
|
||||||
|
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||||
|
|
||||||
|
/******************************************************************************/
|
||||||
|
/* PLL (clocked by HSE) used as System clock source */
|
||||||
|
/******************************************************************************/
|
||||||
|
|
||||||
|
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||||
|
/* Enable HSE */
|
||||||
|
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||||
|
|
||||||
|
/* Wait till HSE is ready and if Time out is reached exit */
|
||||||
|
do
|
||||||
|
{
|
||||||
|
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||||
|
StartUpCounter++;
|
||||||
|
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||||
|
|
||||||
|
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||||
|
{
|
||||||
|
HSEStatus = (uint32_t)0x01;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
HSEStatus = (uint32_t)0x00;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (HSEStatus == (uint32_t)0x01)
|
||||||
|
{
|
||||||
|
/* Enable Prefetch Buffer and set Flash Latency */
|
||||||
|
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||||
|
|
||||||
|
/* HCLK = SYSCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||||
|
|
||||||
|
/* PCLK2 = HCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||||
|
|
||||||
|
/* PCLK1 = HCLK / 2 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||||
|
|
||||||
|
/* PLL configuration */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||||
|
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||||
|
|
||||||
|
/* Enable PLL */
|
||||||
|
RCC->CR |= RCC_CR_PLLON;
|
||||||
|
|
||||||
|
/* Wait till PLL is ready */
|
||||||
|
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Select PLL as system clock source */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||||
|
|
||||||
|
/* Wait till PLL is used as system clock source */
|
||||||
|
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||||
|
configuration. User can add here some code to deal with this error */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
76
src/main/target/SPARKY/system_stm32f30x.h
Normal file
|
@ -0,0 +1,76 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file system_stm32f30x.h
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V1.1.1
|
||||||
|
* @date 28-March-2014
|
||||||
|
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||||
|
* You may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at:
|
||||||
|
*
|
||||||
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup CMSIS
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Define to prevent recursive inclusion
|
||||||
|
*/
|
||||||
|
#ifndef __SYSTEM_STM32F30X_H
|
||||||
|
#define __SYSTEM_STM32F30X_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
extern void SystemInit(void);
|
||||||
|
extern void SystemCoreClockUpdate(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*__SYSTEM_STM32F30X_H */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
88
src/main/target/SPARKY/target.h
Normal file
|
@ -0,0 +1,88 @@
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "SPKY" // SParKY
|
||||||
|
|
||||||
|
#define LED0_GPIO GPIOB
|
||||||
|
#define LED0_PIN Pin_4 // Blue LEDs - PB4
|
||||||
|
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||||
|
#define LED1_GPIO GPIOB
|
||||||
|
#define LED1_PIN Pin_5 // Green LEDs - PB5
|
||||||
|
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||||
|
|
||||||
|
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor
|
||||||
|
#define GYRO
|
||||||
|
#define USE_GYRO_MPU9150
|
||||||
|
|
||||||
|
#define ACC
|
||||||
|
#define USE_ACC_MPU9150
|
||||||
|
|
||||||
|
#define BARO
|
||||||
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
|
#define LED0
|
||||||
|
#define LED1
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7)
|
||||||
|
#define USE_USART2 // Input - RX (PA3)
|
||||||
|
#define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
|
||||||
|
#define SERIAL_PORT_COUNT 4
|
||||||
|
|
||||||
|
#define UART1_TX_PIN GPIO_Pin_6 // PB6
|
||||||
|
#define UART1_RX_PIN GPIO_Pin_7 // PB7
|
||||||
|
#define UART1_GPIO GPIOB
|
||||||
|
#define UART1_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||||
|
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||||
|
|
||||||
|
#define UART2_TX_PIN GPIO_Pin_2 // PA2 - Clashes with PWM6 input.
|
||||||
|
#define UART2_RX_PIN GPIO_Pin_3 // PA3
|
||||||
|
#define UART2_GPIO GPIOA
|
||||||
|
#define UART2_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART2_TX_PINSOURCE GPIO_PinSource2
|
||||||
|
#define UART2_RX_PINSOURCE GPIO_PinSource3
|
||||||
|
|
||||||
|
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP?
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||||
|
|
||||||
|
#define I2C2_SCL_GPIO GPIOA
|
||||||
|
#define I2C2_SCL_GPIO_AF GPIO_AF_4
|
||||||
|
#define I2C2_SCL_PIN GPIO_Pin_9
|
||||||
|
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
|
||||||
|
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||||
|
#define I2C2_SDA_GPIO GPIOA
|
||||||
|
#define I2C2_SDA_GPIO_AF GPIO_AF_4
|
||||||
|
#define I2C2_SDA_PIN GPIO_Pin_10
|
||||||
|
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||||
|
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||||
|
|
||||||
|
|
||||||
|
#define SENSORS_SET (SENSOR_ACC)
|
||||||
|
|
||||||
|
#define SERIAL_RX
|
||||||
|
#define GPS
|
||||||
|
#define DISPLAY
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART2, PA3
|
||||||
|
#define BIND_PORT GPIOA
|
||||||
|
#define BIND_PIN Pin_3
|
|
@ -55,9 +55,9 @@
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* APB1 Prescaler | 2
|
* APB1 Prescaler | 2
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* HSE Frequency(Hz) | 12000000
|
* HSE Frequency(Hz) | 8000000
|
||||||
*----------------------------------------------------------------------------
|
*----------------------------------------------------------------------------
|
||||||
* PLLMUL | 6
|
* PLLMUL | 9
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
* PREDIV | 1
|
* PREDIV | 1
|
||||||
*-----------------------------------------------------------------------------
|
*-----------------------------------------------------------------------------
|
||||||
|
|