1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Merge with upstream

This commit is contained in:
Joel Fuster 2015-01-10 14:31:34 -05:00
commit 09862aed78
80 changed files with 2728 additions and 515 deletions

View file

@ -105,6 +105,12 @@ STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
EXCLUDES = stm32f10x_crc.c \
stm32f10x_cec.c \
stm32f10x_can.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
# Search path and source files for the CMSIS sources
VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
@ -129,6 +135,12 @@ STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
EXCLUDES = stm32f10x_crc.c \
stm32f10x_cec.c \
stm32f10x_can.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
# Search path and source files for the CMSIS sources
VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
@ -219,7 +231,8 @@ HIGHEND_SRC = flight/autotune.c \
telemetry/msp.c \
telemetry/smartport.c \
sensors/sonar.c \
sensors/barometer.c
sensors/barometer.c \
blackbox/blackbox.c
NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_adxl345.c \
@ -354,6 +367,8 @@ CJMCU_SRC = startup_stm32f10x_md_gcc.S \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
blackbox/blackbox.c \
hardware_revision.c \
$(COMMON_SRC)
CC3D_SRC = startup_stm32f10x_md_gcc.S \

View file

@ -79,7 +79,7 @@ https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgein
The source for it is here:
https://github.com/hydra/cleanflight-configurator
https://github.com/cleanflight/cleanflight-configurator
## Contributing

View file

@ -1,11 +1,13 @@
#!/bin/bash
filename=Manual
doc_files=( 'Configuration.md'
'Board - CC3D.md'
'Board - Naze32.md'
'Rx.md'
doc_files=(
'Installation.md'
'Configuration.md'
'Cli.md'
'Serial.md'
'Rx.md'
'Spektrum bind.md'
'Failsafe.md'
'Battery.md'
'Gps.md'
@ -15,8 +17,21 @@ doc_files=( 'Configuration.md'
'Display.md'
'Buzzer.md'
'Sonar.md'
'Profiles.md'
'Modes.md'
'Inflight Adjustments.md'
'Controls.md'
'Autotune.md'
'Migrating from baseflight.md')
'Blackbox.md'
'Migrating from baseflight.md'
'Board - AlienWii32.md'
'Board - CC3D.md'
'Board - CJMCU.md'
'Board - Naze32.md'
'Board - Sparky.md'
'Board - Olimexino.md'
'Board - CheBuzzF3.md'
)
if which gimli >/dev/null; then
echo "Building ${filename}.pdf"

View file

@ -5,9 +5,10 @@ Autotune helps to automatically tune your multirotor.
## Configuration.
Autotune only works in HORIZON or ANGLE mode, before using auto-tune it's best you setup so there is as little drift as possible.
Autotuning is best on a full battery in good flying conditions, i.e. no or minimal wind.
Autotuning is best on a full battery in good flying conditions, i.e. no or minimal wind. Autotune does not support
pid_controller 2 (pid_controller 0 is the Cleanflight default).
Configure a two position switch on your transmitter to activate the AUTOTUNE and HORIZON or ANGLE modes using the auxilary configuration.
Configure a two position switch on your transmitter to activate the AUTOTUNE and (HORIZON or ANGLE) modes using the auxiliary configuration.
You may find a momentary switch more suitable than a toggle switch.
@ -25,15 +26,15 @@ Turn off the autotune switch. If the autotune switch is on while not armed the
1. Turn off/release the switch while still flying to stop this phase of tuning. PID settings will have been updated for PITCH/YAW.
1. PIDS are updated, fly and see if it's better.
1. PIDs are updated, fly and see if it's better.
1. If it's worse, flip the switch again to restore previous pids that were present prior to arming.
1. If it's worse, flip the switch again to restore previous PIDs that were present prior to arming.
1. Land.
1. Verify results via an app while power still applied if desired. Cutting the power will loose the unsaved pids.
1. Verify results via an app with power still applied if desired. Cutting the power will lose the unsaved PIDs.
1. If you're happy with the pids then while disarmed flip the autotune switch again to save all settings then flip it back so you can arm again. A beeper will sound indicating the settings are saved.
1. If you're happy with the PIDs then while disarmed flip the autotune switch again to save all settings then flip it back so you can arm again. A beeper will sound indicating the settings are saved.
# References

View file

@ -1,16 +1,16 @@
# Battery Monitoring
Cleanflight has battery monitoring capability. Battery voltage of the main battery can be measured by the system and used
Cleanflight has a battery monitoring feature. Battery voltage of the main battery can be measured by the system and used
to trigger a low-battery warning buzzer, on-board status LED flashing and LED strip patterns.
Low battery warnings can:
* help to ensure that you have time to safely land the aircraft.
* help maintain the life and safety of your LiPo/LiFe batteries which should not be discharged below manufactures recommendations.
* help maintain the life and safety of your LiPo/LiFe batteries which should not be discharged below manufacturers recommendations.
Minimum and maximum cell voltages can be set, these voltages are used to detect the amount of cells you are using.
Minimum and maximum cell voltages can be set, and these voltages are used to detect the amount of cells you are using.
Per-cell monitoring is not supported.
Per-cell monitoring is not supported, as we only use one ADC to read the battery voltage.
## Supported targets
@ -21,7 +21,8 @@ All targets support battery voltage monitoring unless status.
When dealing with batteries **ALWAYS CHECK POLARITY!**
Measure expected voltages first and then connect to flight controller, connecting to the flight controller with
incorrect voltage or reversed polarity will likely fry your flight controller.
incorrect voltage or reversed polarity will likely fry your flight controller. Ensure that your flight controller
has a voltage divider that is capable of measuring your particular battery voltage.
### Naze32
@ -46,6 +47,8 @@ Configure min/max cell voltages using the following CLI setting:
`vbat_max_cell_voltage` - maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V
`set vbat_warning_cell_voltage` - warning voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 34 = 3.4V
`vbat_min_cell_voltage` - minimum voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 33 = 3.3V
e.g.
@ -53,6 +56,7 @@ e.g.
```
set vbat_scale = 110
set vbat_max_cell_voltage = 43
set vbat_warning_cell_voltage = 34
set vbat_min_cell_voltage = 33
```
@ -60,23 +64,23 @@ set vbat_min_cell_voltage = 33
Current monitoring (Amperage) is supported by connecting a current meter to the appropriate current meter ADC input (See Board documentation).
When enabled Amps, mAh used and capacity remaining calculated and used by the telemetry and OLED display subsystems.
When enabled, Amps, mAh used and capacity remaining are calculated and used by the telemetry and OLED display subsystems.
## Configuration
Enable current monitoring using the cli command
Enable current monitoring using the CLI command
```
feature CURRENT_METER
```
Configure capacity using the `battery_capacity` setting, it takes a value in mAh.
Configure capacity using the `battery_capacity` setting, which takes a value in mAh.
The current meter may need to be configured so that the value read at the ADC input matches actual current draw. Just like you need a voltmeter to correctly calibrate your voltage reading you also need an ammeter to calibrate your current sensor.
Use the following settings to adjust calibrtion.
Use the following settings to adjust calibration.
`current_meter_scale`
`current_meter_offset`
If you're using an OSD that expects the multiwii current meter output value then set `multiwii_current_meter_output` to `1`.
If you're using an OSD that expects the multiwii current meter output value, then set `multiwii_current_meter_output` to `1`.

185
docs/Blackbox.md Normal file
View file

@ -0,0 +1,185 @@
# Blackbox flight data recorder
![Rendered flight log frame](Screenshots/blackbox-screenshot-1.jpg)
## Introduction
This feature transmits your flight data information on every control loop iteration over a serial port to an external
logging device to be recorded.
After your flight, you can process the resulting logs on your computer to either turn them into CSV (comma-separated
values) or render your flight log as a video using the tools `blackbox_decode` and `blackbox_render`. Those tools can be
found in this repository:
https://github.com/cleanflight/blackbox-tools
You can also view your flight logs using your web browser with the interactive log viewer:
https://github.com/cleanflight/blackbox-log-viewer
## Logged data
The blackbox records flight data on every iteration of the flight control loop. It records the current time in
microseconds, P, I and D corrections for each axis, your RC command stick positions (after applying expo curves),
gyroscope data, accelerometer data (after your configured low-pass filtering), barometer readings, 3-axis magnetometer
readings, raw VBAT measurements, and the command being sent to each motor speed controller. This is all stored without
any approximation or loss of precision, so even quite subtle problems should be detectable from the fight data log.
Currently, the blackbox attempts to log GPS data whenever new GPS data is available, but this has not been tested yet.
The CSV decoder and video renderer do not yet show any of the GPS data (though this will be added). If you have a working
GPS, please send in your logs so I can get the decoding implemented.
The data rate for my quadcopter using a looptime of 2400 is about 10.25kB/s. This allows about 18 days of flight logs
to fit on a 16GB MicroSD card, which ought to be enough for anybody :).
## Supported configurations
The maximum data rate for the flight log is fairly restricted, so anything that increases the load can cause the flight
log to drop frames and contain errors.
The Blackbox was developed and tested on a quadcopter. It has also been tested on a tricopter. It should work on
hexacopters or octocopters, but as they transmit more information to the flight log (due to having more motors), the
number of dropped frames may increase. The `blackbox_render` tool only supports tri and quadcopters (please send me
flight logs from other craft, and I can add support for them!)
Cleanflight's `looptime` setting will decide how many times per second an update is saved to the flight log. The
software was developed on a craft with a looptime of 2400. Any looptime smaller than this will put more strain on the
data rate. The default looptime on Cleanflight is 3500. If you're using a looptime of 2000 or smaller, you will probably
need to reduce the sampling rate in the Blackbox settings, see the later section on configuring the Blackbox feature for
details.
## Hardware
The blackbox software is designed to be used with an [OpenLog serial data logger][] and a microSDHC card. You need a
little prep to get the OpenLog ready for use, so here are the details:
### Firmware
The OpenLog ships with standard OpenLog 3 firmware installed. However, in order to reduce the number of dropped frames,
it should be reflashed with the [OpenLog Light firmware][] or the special [OpenLog Blackbox firmware][] . The Blackbox
variant of the firmware ensures that the OpenLog is running at the correct baud-rate and does away for the need for a
`CONFIG.TXT` file to set up the OpenLog.
You can find the Blackbox version of the OpenLog firmware [here](https://github.com/cleanflight/blackbox-firmware),
along with instructions for installing it onto your OpenLog.
[OpenLog serial data logger]: https://www.sparkfun.com/products/9530
[OpenLog Light firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light
[OpenLog Blackbox firmware]: https://github.com/cleanflight/blackbox-firmware
### microSDHC
Your choice of microSDHC card is very important to the performance of the system. The OpenLog relies on being able to
make many small writes to the card with minimal delay, which not every card is good at. A faster SD-card speed rating is
not a guarantee of better performance.
#### microSDHC cards known to have poor performance
- Generic 4GB Class 4 microSDHC card - the rate of missing frames is about 1%, and is concentrated around the most
interesting parts of the log!
#### microSDHC cards known to have good performance
- Transcend 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
- Sandisk Extreme 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
You should format any card you use with the [SD Association's special formatting tool][] , as it will give the OpenLog
the best chance of writing at high speed. You must format it with either FAT, or with FAT32 (recommended).
[SD Association's special formatting tool]: https://www.sdcard.org/downloads/formatter_4/
### OpenLog configuration
This section applies only if you are using the OpenLog or OpenLog Light original firmware on the OpenLog. If you flashed
it with the special OpenLog Blackbox firmware, you don't need to configure it further.
Power up the OpenLog with a microSD card inside, wait 10 seconds or so, then power it down and plug the microSD card
into your computer. You should find a "CONFIG.TXT" file on the card. Edit it in a text editor to set the first number
(baud) to 115200. Set esc# to 0, mode to 0, and echo to 0. Save the file and put the card back into your OpenLog, it
should use those settings from now on.
If your OpenLog didn't write a CONFIG.TXT file, create a CONFIG.TXT file with these contents and store it in the root
of the MicroSD card:
```
115200,26,0,0,1,0,1
baud,escape,esc#,mode,verb,echo,ignoreRX
```
## Enabling this feature (CLI)
Enable the Blackbox feature by typing in `feature BLACKBOX` and pressing enter. You also need to assign the Blackbox to
one of [your serial ports][] . A 115200 baud port is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx
header in the center of the board).
For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough.
Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go!
[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md
[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en
## Configuring this feature
The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control
the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which
decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs
every iteration.
If you are using a short looptime like 2000 or faster, or you're using a slower MicroSD card, you will need to reduce
this rate to reduce the number of corrupted logged frames. A rate of 1/2 is likely to work for most craft.
You can change these settings by entering the CLI tab in the Cleanflight Configurator and using the `set` command, like so:
```
set blackbox_rate_num = 1
set blackbox_rate_denom = 2
```
### Serial port
Connect the "TX" pin of the serial port you've chosen to the OpenLog's "RXI" pin. Don't connect the serial port's RX
pin to the OpenLog.
### Protection
The OpenLog can be wrapped in black electrical tape or heat-shrink in order to insulate it from conductive frames (like
carbon fiber), but this makes its status LEDs impossible to see. I recommend wrapping it with some clear heatshrink
tubing instead.
![OpenLog installed](Wiring/blackbox-installation-1.jpg "OpenLog installed with double-sided tape, SDCard slot pointing outward")
## Usage
The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm. Each time the OpenLog is
power-cycled, it begins a fresh new log file. If you arm and disarm several times without cycling the power (recording
several flights), those logs will be combined together into one file. The command line tools will ask you to pick which
one of these flights you want to display/decode.
If your craft has a buzzer attached, a short beep will be played when you arm. You can later use this beep to
synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line in the flight
data log, which you can sync against the beep in your recorded audio track).
The OpenLog requires a couple of seconds of delay after connecting the battery before it's ready to record, so don't
arm your craft immediately after connecting the battery (you'll probably be waiting for the flight controller to become
ready during that time anyway!)
You should also wait a few seconds after disarming the quad to allow the OpenLog to finish saving its data.
Don't insert or remove the SD card while the OpenLog is powered up.
## Converting logs to CSV or PNG
After your flights, you'll have a series of files labeled "LOG00001.TXT" etc. on the microSD card. You'll need to
decode these with the `blackbox_decode` tool to create a CSV (comma-separated values) file for analysis, or render them
into a series of PNG frames with `blackbox_render` tool, which you could then convert into a video using another
software package.
You'll find those tools along with instructions for using them in this repository:
https://github.com/cleanflight/blackbox-tools
You can also view your .TXT flight log files interactively using your web browser with the Cleanflight Blackbox Explorer
tool:
https://github.com/cleanflight/blackbox-log-viewer
This allows you to scroll around a graphed version of your log and examine your log in detail.

View file

@ -1,6 +1,6 @@
# Board - AlienWii32
The AlienWii32 is actually in prototype stage only a few samples exist. There is some more field testing ongoing. The information below is preliminary and will be updated as needed.
The AlienWii32 is actually in prototype stage and only a few samples exist. There is some more field testing ongoing. The information below is preliminary and will be updated as needed.
Here are the hardware specifications:

View file

@ -2,8 +2,8 @@
The OpenPilot Copter Control 3D aka CC3D is a board more tuned to Acrobatic flying or GPS based
auto-piloting. It only has one sensor, the MPU6000 SPI based Accelerometer/Gyro.
It also features a 16mbit SPI based EEPROM chip. It has 6 ports labelled as inputs (one pin each)
and 6 ports labelled as motor/servo outputs (3 pins each).
It also features a 16Mbit SPI based EEPROM chip. It has 6 ports labeled as inputs (one pin each)
and 6 ports labeled as motor/servo outputs (3 pins each).
If issues are found with this board please report via the [github issue tracker](https://github.com/cleanflight/cleanflight/issues).
@ -11,11 +11,11 @@ The board has a USB port directly connected to the processor. Other boards like
have an on-board USB to uart adapter which connect to the processor's serial port instead.
Currently there is no support for virtual com port functionality on the CC3D which means that cleanflight
does not currently use the USB socket at all. So the communication with the board is achieved through a USB-UART adaptater connected to the Main port.
does not currently use the USB socket at all. Therefore, the communication with the board is achieved through a USB-UART adaptater connected to the Main port.
The board cannot currently be used for hexacopters/octocopters.
Tricopter & Airplane support is untested, please report success failure if you try it.
Tricopter & Airplane support is untested, please report success or failure if you try it.
# Pinouts
@ -26,8 +26,8 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SE
| 1 | Ground | |
| 2 | +5V | |
| 3 | PPM Input | Enable `feature RX_PPM` |
| 4 | Softserial1 TX | Enable `feature SOFTSERIAL` |
| 5 | Softserial1 RX | Enable `feature SOFTSERIAL` |
| 4 | SoftSerial1 TX | Enable `feature SOFTSERIAL` |
| 5 | SoftSerial1 RX | Enable `feature SOFTSERIAL` |
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
| 8 | RSSI | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
@ -40,7 +40,7 @@ The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_S
| 2 | MOTOR 2 | |
| 3 | MOTOR 3 | |
| 4 | MOTOR 4 | |
| 5 | Led Strip | |
| 5 | LED Strip | |
| 6 | Unused | |
The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_PWM mode
@ -71,11 +71,11 @@ The 6 pin RC_Output connector has the following pinouts when used in RX_PARALLEL
| Value | Identifier | Board Markings | Notes |
| ----- | ------------ | -------------- | -----------------------------------------|
| 1 | USART1 | MAIN PORT | Has a hardware inverter for SBUS |
| 1 | USART1 | MAIN PORT | Has a hardware inverter for S.BUS |
| 2 | USART3 | FLEX PORT | |
| 3 | SoftSerial | RC connector | Pins 4 and 5 (Tx and Rx respectively) |
The Softserial port is not available when RX_PARALLEL_PWM is used. The transmission data rate is limited to 19200 baud.
The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmission data rate is limited to 19200 baud.
To connect the GUI to the flight controller you need additional hardware attached to the USART1 serial port (by default).

145
docs/Board - CJMCU.md Normal file
View file

@ -0,0 +1,145 @@
# Board - CJMCU
The CJMCU is a tiny (80mm) board running a STM32F103, which contains a 3-Axis Compass (HMC5883L)
and an Accelerometer/Gyro (MPU6050).
This board does not have an onboard USB-Serial converter, so an external adapter is needed.
# Hardware revisions
| Revision | Notes |
| -------- | ----- |
| 1 | No boot jumper pads by LED1. Uses blue and red LEDs |
| 2 | Boot jumper pads presoldered with pins and a jumper by LED1. Uses green and red LEDs. |
Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards.
# Pins
## RX Connections
| Pin Label | Description |
| --------- | ------------------------ |
| PA0 | RC Channel 1 |
| PA1 | RC Channel 2 |
| PA2 | RC Channel 3 / USART2 TX |
| PA3 | RC Channel 4 / USART2 RX |
| VCC | Power (See note) |
| GND | Ground |
NOTE: The VCC RX Pin is not regulated and will supply what ever voltage is provided to the board, this will mean it'll provide 5v if a 5v serial connection is used. Be careful if you are using a voltage sensitive RX. A regulated 3.3v supply can be found on the top pin of column 1, just below the RX GND pin.
## Serial Connections
USART1 (along with power) is on the following pins.
| Pin Label | Description |
| --------- | --------------- |
| TX1 | UART1 TX |
| RX1 | UART2 RX |
| GND | Ground |
| 3V3 | Power +3.3v |
| 5V | Power +5v |
USART2 is the following pins.
| Pin Label | Description |
| --------- | ----------- |
| PA2 | USART2 TX |
| PA3 | USART2 RX |
## Power Connections
| Pin Label | Description |
| --------- | ----------------------- |
| Power + | Power - 1 Cell 3.7v Max |
| Power - | Ground |
## Motor Connections
In standard QUADX configuration, the motors are mapped:
| Cleanflight | CJMCU |
| ----------- | ------ |
| Motor 1 | Motor3 |
| Motor 2 | Motor2 |
| Motor 3 | Motor4 |
| Motor 4 | Motor1 |
It is therefore simplest to wire the motors:
* Motor 1 -> Clockwise
* Motor 2 -> Anti-Clockwise
* Motor 3 -> Clockwise
* Motor 4 -> Anti-Clockwise
If you are using the Hubsan x4/Ladybird motors, clockwise are Blue (GND) / Red (VCC) wires, anticlockwise
are Black (GND) / White (VCC).
i.e. there is one wire on each motor out of the standard RED/BLACK VCC/GND polarity colors that can be used to identify polarity.
If you have wired as above, Motor1/Motor2 on the board will be forward.
# Connecting a Serial-USB Adapter
You will need a USB -> Serial UART adapter. Connect:
| Adapter | CJMCU |
| ----------------- | -------------------------- |
| Either 3.3v OR 5v | The correct 3.3v OR 5v pin |
| RX | TX |
| TX | RX |
When first connected this should power up the board, and will be in bootloader mode. If this does not happen, check
the charge switch is set to POW.
After the flashing process has been completed, this will allow access via the cleanflight configurator to change
settings or flash a new firmware.
WARNING: If the motors are connected and the board boots into the bootloader, they will start
to spin after around 20 seconds, it is recommended not to connect the motors until the board
is flashed.
# Flashing
To flash the board:
* Open Cleanflight Configurator
* Choose the latest CJMCU firmware from the list.
* Select "Load Firmware [Online]" and wait for the firmware to download.
* Tick "No Reboot Sequence" and "Full Chip Erase"
* Connect the USB->Serial adapter to the board
* Select the USB-UART adapter from the top left box
* Click "Flash Firmware"
* You should see "Programming: SUCCESSFUL" in the log box
* Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown
* Unplug the quad and short the 2 "BOOT0" pins. Revision 1 boards require this to be soldered, revision 2 boards can connect the included jumper to the two pre-soldered pins - This prevents the board from going into bootloader mode on next
boot, if anything goes wrong, simply disconnect these two pins and the bootloader will start, allowing you to reflash. You cannot
overwrite the bootloader.
# Charging
The CJMCU has on it a TP4056 Lithium battery charging IC that can charge a 1S battery at 1A using a provided 5v supply attached to the 5v serial pin.
To charge an attached battery:
* Set the power switch to OFF
* Set the charge switch to CHG
* Plug in a 1S battery to the battery pins
* Plug in a 5v supply to the 5v serial pins
The charger will finish when either the battery reaches 4.2v, or the battery's voltage is greater than the charger's input voltage.
The two nearby LEDs will show the status of charging:
| Status | Green LED | Red LED |
|--------------------|-----------|-----------|
| Charging | On | Off |
| Finished | Off | On |
| 5v not connected | Off | Off |
| Batt not connected | Flashing | On |
# Helpful Hints
* If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500
for one of the the AUX channels which will result in it being always on
* Enabling the feature MOTOR_STOP helps with crashes so it doesn't try to keep spinning on its back
* When the power runs low, the quad will start jumping around a bit, if the flight behaviour seems strange, check your batteries charge

View file

@ -1,100 +0,0 @@
# Board - CMJCU
The CMJCU is a tiny (80mm) board running a STM32F103, which contains a 3-Axis Compass (HMC5883L)
and an Accelerometer/Gyro (MPU6050).
This board does not have an onboard USB-Serial converter, so an external adapter is needed.
# Pins
RX Connections
| Pin Label | Description |
| --------- | ----------- |
| PA0 | Channel 1 |
| PA1 | Channel 2 |
| PA2 | Channel 3 |
| PA3 | Channel 4 |
| VCC | Power +3.3v |
| GND | Ground |
Serial Connections
| Pin Label | Description |
| --------- | --------------- |
| TX1 | Serial Transmit |
| RX1 | Serial Receive |
| GND | Ground |
| 3V3 | Power +3.3v |
| 5V | Power +5v |
Power Connections
| Pin Label | Description |
| --------- | ----------------------- |
| Power + | Power - 1 Cell 3.7v Max |
| Power - | Ground |
Motor Connections
In standard QUADX configuration, the motors are mapped:
| Cleanflight | CMJCU |
| ----------- | ------ |
| Motor 1 | Motor3 |
| Motor 2 | Motor2 |
| Motor 3 | Motor4 |
| Motor 4 | Motor1 |
It is therefore simplest to wire the motors:
* Motor 1 -> Clockwise
* Motor 2 -> Anti-Clockwise
* Motor 3 -> Clockwise
* Motor 4 -> Anti-Clockwise
If you are using the Hubsan x4/Ladybird motors, clockwise are Blue(GND)/Red(VCC) wires, anticlockwise
are Black(GND)/White(VCC)
If you have wired as above, Motor1/Motor2 on the board will be forward.
# Connecting a Serial-USB Adapter
You will need a USB -> Serial UART adapter. Connect:
| Adapter | CMJCU |
| ----------------- | -------------------------- |
| Either 3.3v OR 5v | The correct 3.3v OR 5v pin |
| RX | TX |
| TX | RX |
When first connected this should power up the board, and will be in bootloader mode. If this does not happen, check
the charge switch is set to POW.
After the flashing process has been completed, this will allow access via the cleanflight configurator to change
settings or flash a new firmware.
WARNING: If the motors are connected and the board boots into the bootloader, they will start
to spin after around 20 seconds, it is recommended not to connect the motors until the board
is flashed.
# Flashing
To flash the board:
* Open Cleanflight Configurator
* Download the CMJCU firmware binary (https://github.com/cleanflight/cleanflight/tree/master/obj/cleanflight_CJMCU.hex)
* Select "Load Firmware [Local]" and choose the CMJCU binary
* Tick "No Reboot Sequence" and "Full Chip Erase"
* Connect the USB->Serial adapter to the board
* Select the USB-UART adapter from the top left box
* Click "Flash Firmware"
* You should see "Programming: SUCCESSFUL" in the log box
* Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown
* Unplug the quad and solder across the 2 "BOOT0" pins - This prevents the board from going into bootloader mode on next
boot, if anything goes wrong, simply unsolder these pins and the bootloader will start, allowing you to reflash. You cannot
overwrite the bootloader.
# Helpful Hints
* If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500
for one of the the AUX channels which will result in it being always on
* Enabling the feature MOTOR_STOP helps with crashes so it doesn't try to keep spinning on its back
* When the power runs low, the quad will start jumping around a bit, if the flight behaviour seems strange, check your batteries charge

View file

@ -1,13 +1,12 @@
ChebuzzF3
# Board - ChebuzzF3
Author: Dominic Clifton
The ChebuzzF3 is a daugter board which connects to the bottom of an STM32F3Discovery board and provides pin headers and ports for various FC connections.
All connections were traced using a multimeter and then verified against the TauLabs source code using the revision linked.
https://github.com/TauLabs/TauLabs/blob/816760dec2a20db7fb9ec1a505add240e696c31f/flight/targets/flyingf3/board-info/board_hw_defs.c
Connections
## Connections
Board orientation.
@ -15,7 +14,7 @@ These notes assume that when the board is placed with the header pins facing up,
Inner means between the two rows of header sockets, outer means between the left/right board edges and the header sockets.
SPI2 / External SPI
### SPI2 / External SPI
sclk GPIOB 13
miso GPIOB 14
@ -25,7 +24,7 @@ mosi GPIOB 15
There are 4 pins, labelled CS1-4 next to a label that reads Ext SPI. The 3rd pin is connected to the flash chip on
the bottom right inner of the board. The other pins on the flash chip are wired up to PB3/4/5
SPI3 / SPI
### SPI3 / SPI
sclk GPIOB 3
miso GPIOB 4
@ -36,7 +35,33 @@ ssel 2 GPIOB 11 / Ext SPI CS2
ssel 3 GPIOB 12 / Ext SPI CS3 - wired up to Slave Select of M25P16 15MBitFlash chip
ssel 4 GPIOB 13 / Ext SPI CS4 - not usable since it is used for SPI2 sclk
### RC Input
INPUT
PA8 / CH1 - TIM1_CH1
PB8 / CH2 - TIM16_CH1
PB9 / CH3 - TIM17_CH1
PC6 / CH4 - TIM8_CH1
PC7 / CH5 - TIM8_CH2
PC8 / CH6 - TIM8_CH3
PF9 / CH7 - TIM15_CH1
PF10 / CH8 - TIM15_CH2
### PWM Outputs
OUTPUT
PD12 / CH1 - TIM4_CH1
PD13 / CH2 - TIM4_CH2
PD14 / CH3 - TIM4_CH3
PD15 / CH4 - TIM4_CH4
PA1 / CH5 - TIM2_CH2
PA2 / CH6 - TIM2_CH3
PA3 / CH7 - TIM2_CH4
PB0 / CH8 - TIM3_CH3
PB1 / CH9 - TIM3_CH4
PA4 / CH10 - TIM3_CH2
### Other ports
There is space for a MS5611 pressure sensor at the top left inner of the board.
@ -68,25 +93,3 @@ There are sockets for 5 UARTs labelled USART1-5.
There is a socket labelled RX_IN.
GPIOD 2 / PD2 / RX_IN
INPUT
PA8 / CH1 - TIM1_CH1
PB8 / CH2 - TIM16_CH1
PB9 / CH3 - TIM17_CH1
PC6 / CH4 - TIM8_CH1
PC7 / CH5 - TIM8_CH2
PC8 / CH6 - TIM8_CH3
PF9 / CH7 - TIM15_CH1
PF10 / CH8 - TIM15_CH2
OUTPUT
PD12 / CH1 - TIM4_CH1
PD13 / CH2 - TIM4_CH2
PD14 / CH3 - TIM4_CH3
PD15 / CH4 - TIM4_CH4
PA1 / CH5 - TIM2_CH2
PA2 / CH6 - TIM2_CH3
PA3 / CH7 - TIM2_CH4
PB0 / CH8 - TIM3_CH3
PB1 / CH9 - TIM3_CH4
PA4 / CH10 - TIM3_CH2

View file

@ -7,13 +7,13 @@ if found please report via the [github issue tracker](https://github.com/cleanfl
# Serial Ports
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | --------- | ------------------ | ------------------------------------------------------------------------------------------- |
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | RX / PA10 | TX / PA9 / TELEM | TELEM output is always inverted (for FrSky). Internally connected to USB port via CP2102 IC |
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
| 3 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |
| 4 | SOFTSERIAL2 | RC7 / PB0 | RC8 / PB1 | |
* You cannot use USART1/TX/TX/TELEM pins at the same time.
* You cannot use USART1/TX/TELEM pins at the same time.
* You may encounter flashing problems if you have something connected to the RX/TX pins. Try disconnecting RX/TX.
# Pinouts
@ -33,7 +33,7 @@ The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SER
| 9 | 7 | unused | |
| 10 | 8 | CURRENT | Enable `feature CURRENT_METER` Connect to the output of a current sensor, 0v-3.3v input |
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two softserial ports are made available to use instead.
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two SoftSerial ports are made available to use instead.
| Pin | Identifier | Function | Notes |
| --- | ---------- | -------------- | -------------------------------- |

View file

@ -1,6 +1,12 @@
Olimexino
# Board - Olimexino
Author: Dominic Clifton
The Olimexino is a cheap and widely available development board
This board is not recommended for cleanflight development because many of the pins needed are not broken out to header pins. A better choice for development is the Port103R, EUSTM32F103RB (F1) or the STM32F3Discovery (F3).
## Connections
### RC Input
INPUT
@ -13,6 +19,8 @@ PA7 CH6 - D11 - PWM6 / SOFTSERIAL1 TX
PB0 CH7 - D27 - PWM7 / SOFTSERIAL2 RX
PB1 CH8 - D28 - PWM8 / SOFTSERIAL2 TX
### PWM Output
OUTPUT
PA8 CH1 - PWM9 - D6
PA11 CH2 - PWM10 - USBDM
@ -21,8 +29,7 @@ PB7 CH4 - PWM12 - D9
PB8 CH5 - PWM13 - D14
PB9 CH6 - PWM14 - D24
Olimexino Shield V1 connections
## Olimexino Shield V1
Headers for a CP2102 for UART1

View file

@ -3,7 +3,7 @@
The Sparky is a very low cost and very powerful board.
* 3 hardware serial ports.
* Built-in serial port inverters which allows SBUS receivers to be used without external inverters.
* Built-in serial port inverters which allows S.BUS receivers to be used without external inverters.
* USB (can be used at the same time as the serial ports).
* 10 PWM outputs.
* Dedicated PPM/SerialRX input pin.
@ -17,20 +17,135 @@ Flyable!
Tested with revision 1 board.
## TODO
* Baro - detection works but getting bad readings, disabled for now.
* Led Strip
* Baro - detection works but sending bad readings, disabled for now.
* LED Strip
* ADC
* Sonar
* Display (via Flex port)
* Softserial - though having 3 hardware serial ports makes it a little redundant.
* SoftSerial - though having 3 hardware serial ports makes it a little redundant.
* Airplane PWM mappings.
# Flashing
## Via USART1
## Via Device Firmware Upload (DFU, USB) - Windows
Short the bootloader pads and flash using configurator or the st flashloader tool via USART1.
Unshort bootloader pads after flashing.
These instructions are for flashing the Sparky board under Windows using DfuSE.
Credits go to Thomas Shue (Full video of the below steps can be found here: https://www.youtube.com/watch?v=I4yHiRVRY94)
Required Software:
DfuSE Version 3.0.2 (latest version 3.0.4 causes errors): http://code.google.com/p/multipilot32/downloads/detail?name=DfuSe.rar
STM VCP Driver 1.4.0: http://www.st.com/web/en/catalog/tools/PF257938
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
```
Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive
Download the latest Sparky release (cleanflight_SPARKY.hex) from:
https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive
In your DfuSE folder go to BIN and start DfuFileMgr.exe
Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK
Press: "S19 or Hex.."
Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open
(you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file)
Press: "Generate" and select the .dfu output file and location
If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!"
```
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
Check the windows device manager to make sure the board is recognized correctly.
It should show up as "STM Device in DFU mode" under Universal Serial Bus Controllers
If it shows up as "STMicroelectronics Virtual COM" under Ports (COM & LPT) instead then the board is not in DFU mode. Disconnect the board, short the bootloader pins again while connecting the board.
If the board shows up as "STM 32 Bootloader" device in the device manager, the drivers need to be updated manually.
Select the device in the device manager, press "update drivers", select "manual update drivers" and choose the location where you extracted the STM VCP Drivers, select "let me choose which driver to install". You shoud now be able to select either the STM32 Bootloader driver or the STM in DFU mode driver. Select the later and install.
Then flash the binary as below.
```
In your DfuSE folder go to BIN and start DfuSeDemo.exe
Select the Sparky Board (STM in DFU Mode) from the Available DFU and compatible HID Devices drop down list
Press "Choose.." at the bootom of the window and select the .dfu file created in the previous step
"File correctly loaded" should appear in the status bar
Press "Upgrade" and confirm with "Yes"
The status bar will show the upload progress and confirm that the upload is complete at the end
```
Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal
## Via Device Firmware Upload (DFU, USB) - Mac OS X
These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project.
http://www.open-tx.org/2013/07/15/dfu-util-07-for-mac-taranis-flashing-utility/
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
```
make TARGET=SPARKY clean
make TARGET=SPARKY binary
```
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
Run 'dfu-util -l' to make sure the device is listed, as below.
```
$ dfu-util -l
dfu-util 0.7
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
This program is Free Software and has ABSOLUTELY NO WARRANTY
Please report bugs to dfu-util@lists.gnumonks.org
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
```
Then flash the binary as below.
```
dfu-util -D obj/cleanflight_SPARKY.bin --alt 0 -R -s 0x08000000
```
The output should be similar to this:
```
dfu-util 0.7
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
This program is Free Software and has ABSOLUTELY NO WARRANTY
Please report bugs to dfu-util@lists.gnumonks.org
Opening DFU capable USB device... ID 0483:df11
Run-time device DFU version 011a
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Claiming USB DFU Interface...
Setting Alternate Setting #0 ...
Determining device status: state = dfuERROR, status = 10
dfuERROR, clearing status
Determining device status: state = dfuIDLE, status = 0
dfuIDLE, continuing
DFU mode device DFU version 011a
Device returned transfer size 2048
No valid DFU suffix signature
Warning: File has no DFU suffix
DfuSe interface name: "Internal Flash "
Downloading to address = 0x08000000, size = 76764
......................................
File downloaded successfully
can't detach
Resetting USB to switch back to runtime mode
```
## Via SWD

View file

@ -2,19 +2,19 @@
Cleanflight supports a buzzer which is used for the following purposes, and more:
Low Battery alarm (when battery monitoring enabled)
Notification of calibration complete status.
AUX operated beeping - useful for locating your aircraft after a crash.
Failsafe status.
* Low Battery alarm (when battery monitoring enabled)
* Notification of calibration complete status.
* AUX operated beeping - useful for locating your aircraft after a crash.
* Failsafe status.
Buzzer is enabled by default on platforms that have buzzer connections.
## Types of buzzer supported
The buzzers are enabled/disabled by simply enabling or disabling a GPIO output pin on the board.
This means the buzzer must be able to generate it's own tone simply by having power applied to it.
This means the buzzer must be able to generate its own tone simply by having power applied to it.
Buzzers that need an analogue or PWM signal do not work and will make clicking noises or no sound at all.
Buzzers that need an analog or PWM signal do not work and will make clicking noises or no sound at all.
Examples of a known-working buzzers.

69
docs/Cli.md Normal file
View file

@ -0,0 +1,69 @@
# Command Line Interface (CLI)
Cleanflight has a command line interface (CLI) that can be used to change settings and configure the FC.
## Accessing the CLI.
The CLI can be accessed via the GUI tool or via a terminal emulator connected to the CLI serial port.
1. Connect your terminal emulator to the CLI serial port (which, by default, is the same as the MSP serial port)
2. Use the baudrate specified by cli_baudrate (115200 by default).
3. Send a `#` character.
To save your settings type in 'save', saving will reboot the flight controller.
To exit the CLI without saving power off the flight controller or type in 'exit'.
To see a list of other commands type in 'help' and press return.
To dump your configuration (including the current profile), use the 'dump' command.
See the other documentation sections for details of the cli commands and settings that are available.
## Backup via CLI
Disconnect main power, connect to cli via USB/FTDI.
dump using cli
`rate profile 0`
`profile 0`
`dump`
dump profiles using cli if you use them
`profile 1`
`dump profile`
`profile 2`
`dump profile`
dump rate profiles using cli if you use them
`rate profile 1`
`dump rates`
`rate profile 2`
`dump rates`
copy screen output to a file and save it.
## Restore via CLI.
Use the cli `defaults` command first.
When restoring from a backup it is a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created youwill be able to see the cli changes between firmware versions. For instance, in December 2014 the default GPS navigation PIDs changed. If you blindly restore your backup you would not benefit from these new defaults.
Use the CLI and send all the output from the saved from the backup commands.
Do not send the file too fast, if you do the FC might not be able to keep up when using USART adapters (including built in ones) since there is no hardware serial flow control.
You may find you have to copy/paste a few lines at a time.
Repeat the backup process again!
Compare the two backups to make sure you are happy with your restored settings.
Re-apply any new defaults as desired.

View file

@ -1,16 +1,17 @@
# Configuration
Cleanflight is configured primarilty using the Cleanflight Configurator GUI.
Both the command line interface and gui are accessible by connecting to a serial port on the target,
be it a USB virtual serial port, physical hardware UART port or a softserial port.
Both the command line interface and GUI are accessible by connecting to a serial port on the target,
be it a USB virtual serial port, physical hardware UART port or a SoftSerial port.
See the Serial section for more information and see the Board specific sections for details of the serial ports available on the board you are using.
The GUI cannot currently configure all aspects of the system, the CLI must be used to enable or configure
some features and settings.
See the Serial section for more information.
See the Board specific sections for details of the serial ports available on the board you are using.
__Due to ongoing development, the fact that the GUI cannot yet backup all your settings and automatic chrome updates of the GUI app it is highly advisable to backup your settings (using the CLI) so that when a new version of the configurator or firmware is released you can re-apply your settings.__
## GUI
@ -21,18 +22,14 @@ can be used to interact with the CLI.
[Cleanflight Configurator on Chrome store](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb)
If you cannot use the latest version of the GUI to access the FC due to firmware compatibility issues you can still access the FC via the CLI to backup your settings, or you can install an old version of the configurator.
Old versions of the configurator can be downloaded from the configurator releases page: https://github.com/cleanflight/cleanflight-configurator/releases
See the README file that comes with the configurator for installation instructions.
## CLI
Cleanflight can also be configured by a command line interface.
The CLI can be accessed via the GUI tool or by sending a single '#' character to the main serial port.
To exit the CLI without saving power off the flight controller or type in 'exit'.
To see a list of commands type in 'help' and press return.
To dump your configuration (including the current profile), use the 'dump' command.
See the other documentation sections for details of the cli commands and settings that are available.
See the CLI section of the documentation for more details.

View file

@ -4,7 +4,7 @@
When armed the aircraft is ready to fly and any motors attached will spin when throttle is applied.
By default arming and disarming is done using stick positions. This is disabled when using a switch to arm.
By default arming and disarming is done using stick positions. Arming with stick positions is disabled when using a switch to arm.
## Stick positions
@ -30,3 +30,7 @@ HIGH - the channel value for the mapped channel input is around 2000
| Trim Acc Backwards | HIGH | CENTER | LOW | CENTER |
| Save setting | LOW | LOW | LOW | HIGH |
##### Download a graphic [pdf cheat-sheet](https://multiwii.googlecode.com/svn/branches/Hamburger/MultiWii-StickConfiguration-23_v0-5772156649.pdf) with TX stick commands.
The Latest version of this pdf can always be found [Here](https://code.google.com/p/multiwii/source/browse/#svn%2Fbranches%2FHamburger)

View file

@ -2,8 +2,7 @@
Cleanflight supports displays to provide information to you about your aircraft and cleanflight state.
When the aircraft is armed the display does not update so flight is not affected. When disarmed the display
cycles between various pages.
When the aircraft is armed the display does not update so flight is not affected. When disarmed the display cycles between various pages.
There is currently no way to change the information on the pages, the list of pages or the time between pages - Code submissions via pull-requests are welcomed!
@ -28,18 +27,18 @@ This makes it ideal for aircraft use.
There are various models of SSD1306 boards out there, they are not all equal and some require addtional modifications
before they work. Choose wisely!
Links to screens:
Links to displays:
* [banggood.com](http://www.banggood.com/0_96-Inch-I2C-IIC-SPI-Serial-128-X-64-OLED-LCD-LED-Display-Module-p-922246.html) 0.96 Inch I2C IIC Serial 128 x 64 OLED LCD
* [wide.hk](http://www.wide.hk/products.php?product=I2C-0.96%22-OLED-display-module-%28-compatible-Arduino-%29) I2C 0.96" OLED display module
* [witespyquad.gostorego.com](http://witespyquad.gostorego.com/accessories/readytofly-1-oled-128x64-pid-tuning-display-i2c.html) ReadyToFlyQuads 1" OLED Display
* [multiwiicopter.com](http://www.multiwiicopter.com/products/1-oled) PARIS 1" OLED 128x64 PID tuning screen AIR
The banggood.com screen is the cheapest at the time fo writing and will correctly send I2C ACK signals.
The banggood.com display is the cheapest at the time fo writing and will correctly send I2C ACK signals.
#### Crius CO-16
This screen is best avoided but will work if you modify it.
This display is best avoided but will work if you modify it.
Step 1

View file

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

View file

@ -1,16 +1,16 @@
# GPS
Two GPS protocols are supported. NMEA text and UBLOX Binary.
Two GPS protocols are supported. NMEA text and UBLOX binary.
## Configuration
Enable the GPS from the CLI as follows:
1) first enable the `feature GPS`
2) set the `gps_provider`
3) if required, set your GPS baud rate using `gps_baudrate`
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`.
1. first enable the `feature GPS`
1. set the `gps_provider`
1. if required, set your GPS baud rate using `gps_baudrate`
1. 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.
1. `save`.
Note: GPS packet loss has been observed at 115200. Try using 57600 if you experience this.
@ -58,7 +58,7 @@ 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.
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).
@ -130,3 +130,15 @@ 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
## Hardware
There are many GPS receivers available on the market, people have reported success with the following receivers:
Ublox Neo-7M GPS with Compass and Pedestal Mount
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426

View file

@ -32,8 +32,8 @@ The following adjustments can be made, in flight, as well as on the ground.
* Yaw P I and D
Example scenarios:
Up to 4 3 position switches or pots can be used to adjust 4 different settings at the same time.
A single 2/3/4/5/6/x position switches can be used to make one 3 position switch adjust one setting at a time.
Up to 4 3-position switches or pots can be used to adjust 4 different settings at the same time.
A single 2/3/4/5/6/x position switche can be used to make one 3 position switch adjust one setting at a time.
Any combination of switches and pots can be used. So you could have 6 POS switch.
@ -55,7 +55,7 @@ Hint: With OpenTX transmitters you can combine two momentary OFF-ON switches to
## Configuration
The cli command `adjrange` is used to configure adjustment ranges.
The CLI command `adjrange` is used to configure adjustment ranges.
12 adjustment ranges can be defined.
4 adjustments can be made at the same time, each simultaneous adjustment requires an adjustment slot.
@ -87,8 +87,11 @@ Normally Range Channel and Slot values are grouped together over multiple adjust
The Range Channel and the Adjustment Channel can be the same channel. This is useful when you want a single 3 Position switch to be dedicated
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 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.
The adjustment function is applied to the adjustment channel when range channel is between the range values.
The adjustment is made when the adjustment channel is in the high or low position. high = mid_rc + 200, low = mid_rc - 200. by default this is 1700 and 1300 respectively.
When the Range Channel does not fall into Start/End range the assigned slot will retain it's state and will continue to apply the adjustment. For
this reason ensure that you define enough ranges to cover the range channel's usable range.
### Adjustment function
@ -187,3 +190,23 @@ explained:
When the switch is low, rate profile 0 is selcted.
When the switch is medium, rate profile 1 is selcted.
When the switch is high, rate profile 2 is selcted.
### Configurator examples
The following 5 images show valid configurations. In all cales the enture usable range for the Range Channel is used.
![Configurator example 1](Screenshots/adjustments-rate-profile-selection-via-3pos.png)
![Configurator example 2](Screenshots/adjustments-pitch-and-roll-rate-adjustment-via-3pos.png)
![Configurator example 3](Screenshots/adjustments-pid-via-two-3pos.png)
![Configurator example 4](Screenshots/adjustments-pid-via-6pos-and-3pos.png)
![Configurator example 5](Screenshots/adjustments-rates-via-a-2pos-and-3pos.png)
The following examples shows __incorrect__ configuration - the entire usable range for the Range Channel is not used in both cases.
![Configurator example 6](Screenshots/adjustments-incorrect-config-1.png)
![Configurator example 7](Screenshots/adjustments-incorrect-config-2.png)
In the following example, the incorrect configuraton (above) has been corrected by adding a range that makes 'No changes'.
![Configurator example 7](Screenshots/adjustments-incorrect-config-2-corrected.png)

View file

@ -12,48 +12,6 @@ See the board specific flashing instructions.
When upgrading be sure to backup / dump your existing settings. Some firmware releases are not backwards compatible and default settings are restored when the FC detects an out of date configuration.
## Backup process
## Backup/Restore process
disconnect main power, connect to cli via USB/FTDI.
dump using cli
`rate profile 0`
`profile 0`
`dump`
dump profiles using cli if you use them
`profile 1`
`dump profile`
`profile 2`
`dump profile`
dump rate profiles using cli if you use them
`rate profile 1`
`dump rates`
`rate profile 2`
`dump rates`
copy screen output to a file and save it.
## Restore process
Use the cli `defaults` command first.
When restoring from a backup it is a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created youwill be able to see the cli changes between firmware versions. For instance, in December 2014 the default GPS navigation PIDs changed. If you blindly restore your backup you would not benefit from these new defaults.
Use the CLI and send all the output from the saved from the backup commands.
Do not send the file too fast, if you do the FC might not be able to keep up when using USART adapters (including built in ones) since there is no hardware serial flow control.
You may find you have to copy/paste a few lines at a time.
Repeat the backup process again!
Compare the two backups to make sure you are happy with your restored settings.
Re-apply any new defaults as desired.
See the CLI section of the docs for details on how to backup and restore your configuration via the CLI.

View file

@ -1,4 +1,4 @@
# Led Strip
# LED Strip
Cleanflight supports the use of addressable LED strips. Addressable LED strips allow each LED in the strip to
be programmed with a unique and independant color. This is far more advanced than the normal RGB strips which
@ -22,7 +22,7 @@ Likewise, support for more than 32 LEDs is possible, it just requires additional
## Supported hardware
Only strips of 32 WS2812 LEDs are supported currently. If the strip is longer than 32 leds it does not matter,
Only strips of 32 WS2812 LEDs are supported currently. If the strip is longer than 32 LEDs it does not matter,
but only the first 32 are used.
WS2812 LEDs require an 800khz signal and precise timings and thus requires the use of a dedicated hardware timer.
@ -51,14 +51,14 @@ uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to pow
from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs.
| Target | Pin | Led Strip | Signal |
| Target | Pin | LED Strip | Signal |
| --------------------- | --- | --------- | -------|
| Naze/Olimexino | RC5 | Data In | PA6 |
| CC3D | ??? | Data In | PB4 |
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use softserial and led strips at the same time.
Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time.
Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips
can not be used at the same time at Parallel PWM.
@ -131,9 +131,9 @@ led 4 0,0::
#### Warning
This mode simply uses the leds to flash when warnings occur.
This mode simply uses the LEDs to flash when warnings occur.
| Warning | Led Pattern | Notes |
| Warning | LED Pattern | Notes |
|---------|-------------|-------|
| Arm-lock enabled | flash between green and off | occurs calibration or when unarmed and the aircraft is tilted too much |
| Low Battery | flash red and off | battery monitoring must be enabled. May trigger temporarily under high-throttle due to voltage drop |
@ -145,14 +145,14 @@ Flash patterns appear in order, so that it's clear which warnings are enabled.
This mode shows the flight mode and orientation.
When flight modes are active then the leds are updated to show different colors depending on the mode, placement on the grid and direction.
When flight modes are active then the LEDs are updated to show different colors depending on the mode, placement on the grid and direction.
Leds are set in a specific order:
* Leds that marked as facing up or down.
* Leds that marked as facing west or east AND are on the west or east side of the grid.
* Leds that marked as facing north or south AND are on the north or south side of the grid.
LEDs are set in a specific order:
* LEDs that marked as facing up or down.
* LEDs that marked as facing west or east AND are on the west or east side of the grid.
* LEDs that marked as facing north or south AND are on the north or south side of the grid.
That is, south facing leds have priority.
That is, south facing LEDs have priority.
#### Indicator
@ -214,7 +214,7 @@ LEDs 2, 4, 6 and 8 should be positioned so the face east/north/west/south, respe
LEDs 9-10 should be placed facing down, in the middle
LEDs 11-12 should be placed facing up, in the middle
This is the default so that if you don't want to place LEDs top and bottom in the middle just connect the first 8 leds.
This is the default so that if you don't want to place LEDs top and bottom in the middle just connect the first 8 LEDs.
### Example 16 LED config
@ -314,8 +314,8 @@ This configuration is specifically designed for the [Alien Spider AQ50D PRO 250m
## Troubleshooting
On initial power up the LEDs on the strip will be set to WHITE. This means you can attach a current meter to verify
the current draw if your measurement equipment is fast enough. This also means that you can make sure that each R,G and B LED
in each LED module on the strip is also functioning.
the current draw if your measurement equipment is fast enough. Most 5050 LEDs will draw 0.3 Watts a piece.
This also means that you can make sure that each R,G and B LED in each LED module on the strip is also functioning.
After a short delay the LEDs will show the unarmed color sequence and or low-battery warning sequence.

View file

@ -70,7 +70,7 @@ reason: renamed to `yaw_rate` for consistency
reason: renamed to `yaw_deadband` for consistency
### midrc
reason: renamed to `midrc` for consistency
reason: renamed to `mid_rc` for consistency
### mincheck
reason: renamed to `min_check` for consistency
@ -100,4 +100,4 @@ reason: renamed to `3d_deadband_throttle` for consistency
reason: renamed to `3d_neutral` for consistency
### alt_hold_throttle_neutral
reason: renamed to 'alt_hold_deadband'
reason: renamed to `alt_hold_deadband` for consistency

View file

@ -42,9 +42,9 @@ WORK-IN-PROGRESS. This mode is not reliable yet, please share your experiences
In this mode the aircraft attempts to return to the GPS position recorded when the aircraft was armed.
This mode should be enabled in conjunction with Angle or Horizion modes and an Altitude hold mode.
This mode should be enabled in conjunction with Angle or Horizon modes and an Altitude hold mode.
Requires a 3D GPS fix and minimum of 5 satallites in view.
Requires a 3D GPS fix and minimum of 5 satellites in view.
## GPS Position Hold
@ -54,15 +54,15 @@ In this mode the aircraft attempts to stay at the same GPS position, as recorded
Disabling and re-enabling the mode will reset the GPS hold position.
This mode should be enabled in conjunction with Angle or Horizion modes and an Altitude hold mode.
This mode should be enabled in conjunction with Angle or Horizon modes and an Altitude hold mode.
Requires a 3D GPS fix and minimum of 5 satallites in view.
Requires a 3D GPS fix and minimum of 5 satellites in view.
## Auxillary Configuration
Spare auxillary receiver channels can be used to enable/disable modes. Some modes can only be enabled this way.
Configure your transmitter so that switches or dial (pots) send channel data on channels 5 upwards.
Configure your transmitter so that switches or dial (pots) send channel data on channels 5 and upwards.
e.g. You can configure a 3 position switch to send 1000 when the switch is low, 1500 when the switch is in the middle and 2000 when the switch is high.
Configure your tx/rx channel limits to use values between 1000 and 2000.
@ -87,7 +87,9 @@ e.g.
Configure AUX range slot 0 to enable ARM when AUX1 is withing 1700 and 2100.
```aux 0 0 0 1700 2100```
```
aux 0 0 0 1700 2100
```
You can display the aux configuration by using the `aux` command with no arguments.
You can display the AUX configuration by using the `aux` command with no arguments.

View file

@ -2,7 +2,7 @@
A profile is a set of configuration settings.
Current 3 profiles are supported, The default profile is profile `0`.
Currently three profiles are supported. The default profile is profile `0`.
## Changing profiles
@ -14,7 +14,7 @@ Profiles can be slected using a GUI or the following stick combinations
| 1 | Down | Left | Up | Middle |
| 2 | Down | Left | Middle | Right |
The cli `profile` command can also be used:
The CLI `profile` command can also be used:
```
profile <index>
@ -26,7 +26,7 @@ Cleanflight supports rate profiles in addition to regular profiles.
Rate profiles contain settings that adjust how your craft behaves based on control input.
3 rate profiles are supported.
Three rate profiles are supported.
Rate profiles can be selected while flying using the inflight adjustments feature.

View file

@ -1,21 +1,21 @@
# RSSI
RSSI is a measurement of signal strength. RSSI is very handy so you know when you are going out of range or there is interference.
RSSI is a measurement of signal strength and is very handy so you know when your aircraft isw going out of range or if it is suffering RF interference.
Some receivers have RSSI outputs. 3 types are supported.
1. RSSI via PPM channel
2. RSSI via Parallel PWM channel
3. RSSI via ADC with PPM RC that has an RSSI output - aka RSSI ADC
1. RSSI via Parallel PWM channel
1. RSSI via ADC with PPM RC that has an RSSI output - aka RSSI ADC
## RSSI via PPM
Configure your receiver to output RSSI on a spare channel, then select the channel used via the cli.
Configure your receiver to output RSSI on a spare channel, then select the channel used via the CLI.
e.g. if you used channel 1 then you would set:
e.g. if you used channel 9 then you would set:
```
set rssi_channel = 1
set rssi_channel = 9
```
## RSSI via Parallel PWM channel
@ -29,7 +29,7 @@ Use inline resistors to lower voltage if required; inline smoothing capacitors m
A simple PPM->RSSI conditioner can easily be made. See the PPM-RSSI conditioning.pdf for details.
Under CLI :
- enable using the RSSI_ADC feature : feature RSSI_ADC
- enable using the RSSI_ADC feature : `feature RSSI_ADC`
- set the RSSI_SCALE parameter (between 1 and 255) to adjust RSSI level according to your configuration.

View file

@ -1,43 +1,67 @@
# Receivers (RX)
## Parallel PWM
A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand.
There are 3 basic types of receivers:
Parallel PWM Receivers
PPM Receivers
Serial Receivers
## Parallel PWM Receivers
8 channel support, 1 channel per input pin. On some platforms using parallel input will disable the use of serial ports
and softserial making it hard to use telemetry or gps features.
and SoftSerial making it hard to use telemetry or GPS features.
## PPM (PPM SUM)
## PPM Receivers
12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications.
PPM is sometimes known as PPM SUM or CPPM.
## MultiWii serial protocol (MSP)
12 channels via a single input pin, not as accurate or jitter free as methods that use serial communications, but readily available.
Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
These receivers are reported working:
## Spektrum
FrSky D4R-II
http://www.frsky-rc.com/product/pro.php?pro_id=24
12 channels via serial currently supported.
Graupner GR24
http://www.graupner.de/en/products/33512/product.aspx
## SBUS
R615X Spektrum/JR DSM2/DSMX Compatible 6Ch 2.4GHz Receiver w/CPPM
http://orangerx.com/2014/05/20/r615x-spektrumjr-dsm2dsmx-compatible-6ch-2-4ghz-receiver-wcppm-2/
16 channels via serial currently supported.
FrSky D8R-XP 8ch telemetry receiver, or CPPM and RSSI enabled receiver
http://www.frsky-rc.com/product/pro.php?pro_id=21
## XBus
## Serial Receivers
The firmware currently supports the MODE B version of the XBus protocol.
Make sure to set your TX to use "MODE B" for XBUS in the TX menus!
See here for info on JR's XBus protocol: http://www.jrpropo.com/english/propo/XBus/
### Spektrum
Tested hardware: JR XG14 + RG731BX with NAZE32 (rev4)
With the current CLI configuration:
`set serialrx_provider=5`
`set serial_port_2_scenario=3`
`feature RX_SERIAL`
8 channels via serial currently supported.
This will set the FW to use serial RX, with XBUS_MODE_B as provider and finally the scenario to be used for serial port 2.
Please note that your config may vary depending on hw used.
These receivers are reported working:
### OpenTX configuration
Lemon Rx DSMX Compatible PPM 8-Channel Receiver + Lemon DSMX Compatible Satellite with Failsafe
http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
### S.BUS
16 channels via serial currently supported. See the Serial chapter in the documentation for a configuration example.
* In most cases you will need an inverter between the receiver output and the flight controller hardware.
* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used.
* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command).
These receivers are reported working:
FrSky X4RSB 3/16ch Telemetry Receiver
http://www.frsky-rc.com/product/pro.php?pro_id=135
FrSky X8R 8/16ch Telemetry Receiver
http://www.frsky-rc.com/product/pro.php?pro_id=105
#### OpenTX S.BUS configuration
If using OpenTX set the transmitter module to D16 mode and select CH1-16 on the transmitter before binding to allow reception
of 16 channels.
@ -46,20 +70,58 @@ OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug -
The bug prevents use of all 16 channels. Upgrade to the latest OpenTX version to allow correct reception of all 16 channels,
without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
## SUMD
### XBUS
The firmware currently supports the MODE B version of the XBus protocol.
Make sure to set your TX to use "MODE B" for XBUS in the TX menus!
See here for info on JR's XBUS protocol: http://www.jrpropo.com/english/propo/XBus/
These receivers are reported working:
XG14 14ch DMSS System w/RG731BX XBus Receiver
http://www.jramericas.com/233794/JRP00631/
### SUMD
16 channels via serial currently supported.
## SUMH
These receivers are reported working:
GR-24 receiver HoTT
http://www.graupner.de/en/products/33512/product.aspx
Graupner receiver GR-12SH+ HoTT
http://www.graupner.de/en/products/870ade17-ace8-427f-943b-657040579906/33565/product.aspx
### SUMH
8 channels via serial currently supported.
SUMH is a legacy Graupner protocol. Graupner have issued a firmware updates for many recivers that lets them use SUMD instead.
### Configuration
## MultiWii serial protocol (MSP)
See the Configuration document some some RX configuration examples.
Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` cli setting as follows.
## Configuration
There are 3 features that control receiver mode:
```
RX_PPM
RX_SERIAL
RX_PARALLEL_PWM
RX_MSP
```
Only one receiver feature can be enabled at a time.
### Serial RX
See the Serial chapter for some some RX configuration examples.
For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as follows.
| Serial RX Provider | Value |
| ------------------ | ----- |
@ -71,11 +133,11 @@ For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` cli setting as
| XBUS_MODE_B | 5 |
#### PPM/PWM input filtering.
### PPM/PWM input filtering.
Hardware input filtering can be enabled if you are experiencing interference on the signal sent via your PWM/PPM RX.
Use the `input_filtering_mode` cli setting to select a mode.
Use the `input_filtering_mode` CLI setting to select a mode.
| Value | Meaning |
| ----- | --------- |

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 147 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 89 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 242 KiB

View file

@ -1,9 +1,9 @@
# Serial
Cleanflight has enhanced serial port flexibility and configuration is slightly more complex as a result.
Cleanflight has enhanced serial port flexibility but configuration is slightly more complex as a result.
Cleanflight has the concept of a function (MSP, GPS, Serial RX, etc) and a port (VCP, UARTx, SoftSerial x).
Not all functions can be used on all ports due to hardware pin mapping, conflicting features, hardware and software
Not all functions can be used on all ports due to hardware pin mapping, conflicting features, hardware, and software
constraints.
## Serial port types
@ -14,11 +14,11 @@ a dedicated USB to UART adapter. VCP does not 'use' a physical UART port.
* SoftSerial - A pair of hardware transmit and receive pins with signal detection and generation done in software.
UART is the most efficent in terms of CPU usage.
SoftSerial is the least efficient and slowest, softserial should only be used for low-bandwith usages, such as telemetry transmission.
SoftSerial is the least efficient and slowest, SoftSerial should only be used for low-bandwith usages, such as telemetry transmission.
UART ports are sometimes exposed via on-board USB to UART converters, such as the CP2102 as found on the Naze and Flip32 boards.
If the flight controller does not have an onboard USB to UART converter and doesn't support VCP then an external USB to UART board is required.
These are sometimes referred to as FTDI boards. FTDI is just a common manufacter of a chip (the FT232RL) used on USB to UART boards.
These are sometimes referred to as FTDI boards. FTDI is just a common manufacturer of a chip (the FT232RL) used on USB to UART boards.
When selecting a USB to UART converter choose one that has DTR exposed as well as a selector for 3.3v and 5v since they are more useful.
@ -31,7 +31,7 @@ Both SoftSerial and UART ports can be connected to your computer via USB to UART
## Serial Configuration
To make configuration easier common usage scenarios are listed below.
To make configuration easier, common usage scenarios are listed below.
### Serial port scenarios
@ -46,20 +46,26 @@ To make configuration easier common usage scenarios are listed below.
7 GPS-PASSTHROUGH ONLY
8 MSP ONLY
9 SMARTPORT TELEMETRY ONLY
10 BLACKBOX ONLY
11 MSP, CLI, BLACKBOX, GPS-PASSTHROUGH
```
### Constraints
If the configuration is invalid the serial port configuration will reset to its defaults and features may be disabled.
* There must always be a port available to use for MSP
* There must always be a port available to use for CLI
* To use a port for a function, the function's corresponding feature must be enabled first.
e.g. to use GPS enable the GPS feature.
* If the configuration is invalid the serial port configuration will reset to it's defaults and features may be disabled.
* If softserial is used be aware that both softserial ports must use the same baudrate.
* There can only be 1 CLI port.
* There is a maximum of 2 MSP ports.
* To use a port for a function, the function's corresponding feature must be also be enabled.
e.g. after configuring a port for GPS enable the GPS feature.
* If SoftSerial is used, then all SoftSerial ports must use the same baudrate.
### Examples
All examples assume default configuration (via cli `defaults` command)
All examples assume default configuration (via CLI `defaults` command)
a) Parallel PWM, GPS and FrSky TELEMETRY (when armed)
@ -74,7 +80,7 @@ set serial_port_2_scenario = 2
save
```
b) Graupner SumD RX SERIAL and HoTT TELEMETRY via Softserial
b) Graupner SumD RX SERIAL and HoTT TELEMETRY via SoftSerial
- MSP,CLI,GPS PASSTHROUGH on UART1
- RX SERIAL on UART2
@ -92,7 +98,7 @@ set serial_port_3_scenario = 4
save
```
c) PPM RX, GPS and FrSky TELEMETRY via softserial
c) PPM RX, GPS and FrSky TELEMETRY via SoftSerial
- MSP, CLI, GPS PASSTHROUGH on UART1
- GPS on UART2
@ -109,7 +115,7 @@ set serial_port_2_scenario = 2
set serial_port_3_scenario = 4
save
```
d) RX SERIAL, GPS and TELEMETRY (when armed) MSP/CLI via softserial
d) RX SERIAL, GPS and TELEMETRY (when armed) MSP/CLI via SoftSerial
- GPS on UART1
- RX SERIAL on UART2
@ -162,7 +168,7 @@ set telemetry_provider = 1
save
```
g) SBus RX SERIAL
g) S.BUS RX SERIAL
- TELEMETRY, MSP, CLI, GPS PASSTHROUGH on UART1
- RX SERIAL on UART2
@ -191,8 +197,8 @@ save
i) MSP via USART1 and SoftSerial 1
- TELEMETRY, MSP, CLI, GPS PASSTHROUGH on UART1
- MSP on SPFTSERIAL1
- Both ports will be at 19200 (limited by softserial)
- MSP on SOFTSERIAL1
- Both ports will be at 19200 (limited by SoftSerial)
- USART2 can still be used for GPS/SerialRX/Telemetry, etc.
```

View file

@ -4,8 +4,7 @@ A sonar sensor can be used to measure altitude for use with BARO and SONAR altit
hold modes.
The sonar sensor is used instead of the pressure sensor (barometer) at low altitudes.
The sonar sensor is only used when the aircraft inclination angle is small.
The sonar sensor is only used when the aircraft inclination angle (attitude) is small.
## Hardware
@ -28,4 +27,4 @@ Current meter cannot be used in conjunction with Parallel PWM and Sonar.
| ------------- | ------------- | ------------------- |
| PB0 / RC7 | PB1 / RC8 | YES (3.3v input) |
Current meter cannot be used in conjunction sonar.
Current meter cannot be used in conjunction with sonar.

View file

@ -20,7 +20,7 @@ This is to activate the hardware bind plug feature
## Hardware
The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienWii32 firmware is build. The hardware bind plug is expected between the defined bind pin and ground.
The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienWii32 firmware is built. The hardware bind plug is expected between the defined bind pin and ground.
## Function

View file

@ -41,7 +41,7 @@ FrSky telemetry signals are inverted. To connect a cleanflight capable board to
For 1, just connect your inverter to a usart or software serial port.
For 2 and 3 use the cli command as follows:
For 2 and 3 use the CLI command as follows:
```
set telemetry_inversion = 1
@ -51,7 +51,7 @@ set telemetry_inversion = 1
RPM shows throttle output when armed.
RPM shows when diarmed.
TEMP2 shows Satallite Signal Quality when GPS is enabled.
TEMP2 shows Satellite Signal Quality when GPS is enabled.
RPM requires that the 'blades' setting is set to 12 on your receiver/display - tested with Taranis/OpenTX.
@ -77,7 +77,7 @@ The diode should be arranged to allow the data signals to flow the right way
As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
Note: The softserial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description section. Verify if you require a 5v/3.3v level shifters.
Note: The SoftSerial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description section. Verify if you require a 5v/3.3v level shifters.
## MultiWii Serial Protocol (MSP)
@ -92,5 +92,3 @@ Smartport is a telemetry system used by newer FrSky transmitters and receivers s
Smartport telemetry is currently experimental, more information can be found here: https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port
In time this documentation will be updated with further details.

Binary file not shown.

After

Width:  |  Height:  |  Size: 194 KiB

View file

@ -32,8 +32,8 @@
/* Includes ------------------------------------------------------------------*/
/* Comment the line below to disable peripheral header file inclusion */
#include "stm32f30x_adc.h"
#include "stm32f30x_can.h"
#include "stm32f30x_crc.h"
//#include "stm32f30x_can.h"
//#include "stm32f30x_crc.h"
#include "stm32f30x_comp.h"
#include "stm32f30x_dac.h"
#include "stm32f30x_dbgmcu.h"

View file

@ -27,9 +27,9 @@
/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */
#include "stm32f10x_adc.h"
#include "stm32f10x_bkp.h"
#include "stm32f10x_can.h"
#include "stm32f10x_cec.h"
#include "stm32f10x_crc.h"
//#include "stm32f10x_can.h"
//#include "stm32f10x_cec.h"
//#include "stm32f10x_crc.h"
#include "stm32f10x_dac.h"
#include "stm32f10x_dbgmcu.h"
#include "stm32f10x_dma.h"

View file

@ -141,7 +141,12 @@ void SetSysClock(bool overclock)
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
#if defined(CJMCU)
// On CJMCU new revision boards (Late 2014) bit 15 of GPIOC->IDR is '1'.
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9;
#else
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
#endif
switch (clocksrc) {
case SRC_HSE:
if (overclock) {

1273
src/main/blackbox/blackbox.c Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,47 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "common/axis.h"
#include <stdint.h>
typedef struct blackboxValues_t {
uint32_t time;
int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
int16_t rcCommand[4];
int16_t gyroData[XYZ_AXIS_COUNT];
int16_t accSmooth[XYZ_AXIS_COUNT];
int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS];
uint16_t vbatLatest;
#ifdef BARO
int32_t BaroAlt;
#endif
#ifdef MAG
int16_t magADC[XYZ_AXIS_COUNT];
#endif
} blackboxValues_t;
void initBlackbox(void);
void handleBlackbox(void);
void startBlackbox(void);
void finishBlackbox(void);

View file

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
FLIGHT_LOG_FIELD_CONDITION_TRICOPTER,
FLIGHT_LOG_FIELD_CONDITION_MAG = 20,
FLIGHT_LOG_FIELD_CONDITION_BARO,
FLIGHT_LOG_FIELD_CONDITION_VBAT,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
FLIGHT_LOG_FIELD_CONDITION_NEVER = 255,
} FlightLogFieldCondition;
typedef enum FlightLogFieldPredictor {
//No prediction:
FLIGHT_LOG_FIELD_PREDICTOR_0 = 0,
//Predict that the field is the same as last frame:
FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1,
//Predict that the slope between this field and the previous item is the same as that between the past two history items:
FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2,
//Predict that this field is the same as the average of the last two history items:
FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3,
//Predict that this field is minthrottle
FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4,
//Predict that this field is the same as motor 0
FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5,
//This field always increments
FLIGHT_LOG_FIELD_PREDICTOR_INC = 6,
//Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set)
FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7,
//Predict 1500
FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8,
//Predict vbatref, the reference ADC level stored in the header
FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9
} FlightLogFieldPredictor;
typedef enum FlightLogFieldEncoding {
FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte
FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte
FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits
FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6,
FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7,
FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8,
FLIGHT_LOG_FIELD_ENCODING_NULL = 9 // Nothing is written to the file, take value to be zero
} FlightLogFieldEncoding;
typedef enum FlightLogFieldSign {
FLIGHT_LOG_FIELD_UNSIGNED = 0,
FLIGHT_LOG_FIELD_SIGNED = 1
} FlightLogFieldSign;
typedef enum FlightLogEvent {
FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
FLIGHT_LOG_EVENT_LOG_END = 255
} FlightLogEvent;

View file

@ -447,6 +447,11 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif
#ifdef BLACKBOX
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
featureSet(FEATURE_RX_SERIAL);
@ -571,19 +576,28 @@ void activateConfig(void)
activateControlRateConfig();
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile);
useRcControlsConfig(
currentProfile->modeActivationConditions,
&masterConfig.escAndServoConfig,
&currentProfile->pidProfile
);
useGyroConfig(&masterConfig.gyroConfig);
#ifdef TELEMETRY
useTelemetryConfig(&masterConfig.telemetryConfig);
#endif
setPIDController(currentProfile->pidController);
#ifdef GPS
gpsUseProfile(&currentProfile->gpsProfile);
gpsUsePIDs(&currentProfile->pidProfile);
#endif
useFailsafeConfig(&currentProfile->failsafeConfig);
setAccelerationTrims(&masterConfig.accZero);
mixerUseConfigs(
currentProfile->servoConf,
&masterConfig.flight3DConfig,
@ -600,8 +614,18 @@ void activateConfig(void)
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
imuRuntimeConfig.small_angle = masterConfig.small_angle;
configureImu(&imuRuntimeConfig, &currentProfile->pidProfile, &currentProfile->accDeadband);
configureAltitudeHold(&currentProfile->pidProfile, &currentProfile->barometerConfig, &currentProfile->rcControlsConfig, &masterConfig.escAndServoConfig);
configureImu(
&imuRuntimeConfig,
&currentProfile->pidProfile,
&currentProfile->accDeadband
);
configureAltitudeHold(
&currentProfile->pidProfile,
&currentProfile->barometerConfig,
&currentProfile->rcControlsConfig,
&masterConfig.escAndServoConfig
);
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);

View file

@ -40,7 +40,8 @@ typedef enum {
FEATURE_RSSI_ADC = 1 << 15,
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
FEATURE_ONESHOT125 = 1 << 18
FEATURE_ONESHOT125 = 1 << 18,
FEATURE_BLACKBOX = 1 << 19
} features_e;
bool feature(uint32_t mask);

View file

@ -85,6 +85,8 @@ typedef struct master_t {
uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
uint8_t blackbox_rate_num;
uint8_t blackbox_rate_denom;
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum

View file

@ -48,4 +48,20 @@
#define LED1_ON
#endif
#ifdef LED2
#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN);
#ifndef LED2_INVERTED
#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN);
#else
#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN);
#endif // inverted
#else
#define LED2_TOGGLE
#define LED2_OFF
#define LED2_ON
#endif
void ledInit(void);

View file

@ -46,6 +46,12 @@ void ledInit(void)
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED2
{
.gpio = LED2_GPIO,
.cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};
@ -58,9 +64,13 @@ void ledInit(void)
#ifdef LED1
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
#endif
#ifdef LED2
RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE);
#endif
LED0_OFF;
LED1_OFF;
LED2_OFF;
for (i = 0; i < gpio_count; i++) {
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);

View file

@ -45,6 +45,11 @@ extern uint16_t cycleTime;
int16_t heading, magHold;
int16_t axisPID[3];
#ifdef BLACKBOX
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
#endif
uint8_t dynP8[3], dynI8[3], dynD8[3];
static int32_t errorGyroI[3] = { 0, 0, 0 };
@ -189,7 +194,8 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
UNUSED(controlRateConfig);
// **** PITCH & ROLL & YAW PID ****
prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500]
prop = min(max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])), 500); // range [0;500]
for (axis = 0; axis < 3; axis++) {
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
// observe max inclination
@ -246,6 +252,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
delta1[axis] = delta;
DTerm = (deltaSum * dynD8[axis]) / 32;
axisPID[axis] = PTerm + ITerm - DTerm;
#ifdef BLACKBOX
axisPID_P[axis] = PTerm;
axisPID_I[axis] = ITerm;
axisPID_D[axis] = -DTerm;
#endif
}
}
@ -329,6 +341,12 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
// -----calculate total PID output
axisPID[axis] = PTerm + ITerm + DTerm;
#ifdef BLACKBOX
axisPID_P[axis] = PTerm;
axisPID_I[axis] = ITerm;
axisPID_D[axis] = DTerm;
#endif
}
}

View file

@ -127,6 +127,8 @@ extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AX
extern int32_t accSum[XYZ_AXIS_COUNT];
extern int16_t axisPID[XYZ_AXIS_COUNT];
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
extern int16_t heading, magHold;
extern int32_t AltHold;

View file

@ -121,6 +121,5 @@ void writeAllMotors(int16_t mc);
void mixerLoadMix(int index, motorMixer_t *customMixers);
void mixerResetMotors(void);
void mixTable(void);
void filterServos(void);
void writeServos(void);
void writeMotors(void);

View file

@ -62,7 +62,10 @@ const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUN
SCENARIO_CLI_ONLY,
SCENARIO_GPS_PASSTHROUGH_ONLY,
SCENARIO_MSP_ONLY,
SCENARIO_SMARTPORT_TELEMETRY_ONLY
SCENARIO_SMARTPORT_TELEMETRY_ONLY,
SCENARIO_BLACKBOX_ONLY,
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH
};
static serialConfig_t *serialConfig;
@ -81,7 +84,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
#endif
};
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
{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},
@ -102,7 +105,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
};
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
@ -118,7 +121,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
#endif
};
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
{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},
#if (SERIAL_PORT_COUNT > 2)
@ -136,7 +139,8 @@ const functionConstraint_t functionConstraints[] = {
{ FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
{ FUNCTION_SERIAL_RX, 9600, 115200, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
{ FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE },
{ FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE }
{ FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE },
{ FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE }
};
#define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
@ -544,9 +548,10 @@ serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
{
uint32_t portIndex = 0, serialPortIdentifier;
uint32_t portIndex = 0, serialPortIdentifier, constraintIndex;
for (serialPortIdentifier = 0; serialPortIdentifier < SERIAL_PORT_IDENTIFIER_COUNT && portIndex < SERIAL_PORT_COUNT; serialPortIdentifier++) {
for (constraintIndex = 0; constraintIndex < SERIAL_PORT_COUNT && portIndex < SERIAL_PORT_COUNT; constraintIndex++) {
serialPortIdentifier = serialPortConstraints[constraintIndex].identifier;
uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
if (functionIndex == IDENTIFIER_NOT_FOUND) {
continue;

View file

@ -25,7 +25,8 @@ typedef enum {
FUNCTION_SMARTPORT_TELEMETRY = (1 << 3),
FUNCTION_SERIAL_RX = (1 << 4),
FUNCTION_GPS = (1 << 5),
FUNCTION_GPS_PASSTHROUGH = (1 << 6)
FUNCTION_GPS_PASSTHROUGH = (1 << 6),
FUNCTION_BLACKBOX = (1 << 7)
} serialPortFunction_e;
typedef enum {
@ -52,10 +53,12 @@ typedef enum {
SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH,
SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX,
SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY,
SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY
SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY,
SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX,
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH
} serialPortFunctionScenario_e;
#define SERIAL_PORT_SCENARIO_COUNT 10
#define SERIAL_PORT_SCENARIO_COUNT 12
#define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
@ -73,42 +76,18 @@ typedef enum {
#endif
} serialPortIndex_e;
#ifdef STM32F303xC
typedef enum {
SERIAL_PORT_USB_VCP = 0,
SERIAL_PORT_USART1,
SERIAL_PORT_USART2,
SERIAL_PORT_USART3,
SERIAL_PORT_USART4
} serialPortIdentifier_e;
#define SERIAL_PORT_IDENTIFIER_COUNT 5
#else
#ifdef CC3D
typedef enum {
SERIAL_PORT_USART1 = 0,
SERIAL_PORT_USART3,
SERIAL_PORT_SOFTSERIAL1,
} serialPortIdentifier_e;
#define SERIAL_PORT_IDENTIFIER_COUNT 3
#else
// serial port identifiers are now fixed, these values are used by MSP commands.
typedef enum {
SERIAL_PORT_USART1 = 0,
SERIAL_PORT_USART2,
SERIAL_PORT_USART3,
SERIAL_PORT_SOFTSERIAL1,
SERIAL_PORT_SOFTSERIAL2
SERIAL_PORT_USART4,
SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2,
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e;
#define SERIAL_PORT_IDENTIFIER_COUNT 5
#endif
#endif
// bitmask
typedef enum {
@ -125,6 +104,7 @@ typedef struct serialPortConstraint_s {
uint32_t maxBaudRate;
serialPortFeature_t feature;
} serialPortConstraint_t;
extern const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT];
typedef struct serialPortFunction_s {
serialPortIdentifier_e identifier;

View file

@ -135,7 +135,8 @@ static const char * const featureNames[] = {
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", NULL
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
"BLACKBOX", NULL
};
// sync this with sensors_e
@ -219,7 +220,7 @@ const clivalue_t valueTable[] = {
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
{ "rssi_scale", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
{ "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE, &masterConfig.inputFilteringMode, 0, 1 },
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
@ -406,6 +407,9 @@ const clivalue_t valueTable[] = {
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
};
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))

View file

@ -98,7 +98,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
* API consumers should ALWAYS handle communication failures gracefully and attempt to continue
* without the information if possible. Clients MAY log/display a suitable message.
*
* API clients should NOT attempt any communication if they can't handle the API MAJOR VERSION.
* API clients should NOT attempt any communication if they can't handle the returned API MAJOR VERSION.
*
* API clients SHOULD attempt communication if the API MINOR VERSION has increased from the time
* the API client was written and handle command failures gracefully. Clients MAY disable
@ -121,7 +121,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 0 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_MINOR 2 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2
@ -154,21 +154,11 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define CAP_NAVCAP ((uint32_t)1 << 4)
#define CAP_EXTAUX ((uint32_t)1 << 5)
/**
* Returns MSP protocol version
* API version
* Flight Controller Identifier
* Flight Controller build version (major, minor, patchlevel)
* Board Identifier
* Board Hardware Revision
* Build Date - "MMM DD YYYY" MMM = Jan/Feb/...
* Build Time - "HH:MM:SS"
* SCM reference length
* SCM reference (git revision, svn commit id)
* Additional FC information length
* Additional FC information (as decided by the FC, for FC specific tools to use as required)
**/
#define MSP_API_VERSION 1 //out message
#define MSP_FC_VARIANT 2 //out message
#define MSP_FC_VERSION 3 //out message
#define MSP_BOARD_INFO 4 //out message
#define MSP_BUILD_INFO 5 //out message
//
// MSP commands for Cleanflight original features
@ -206,6 +196,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_ADJUSTMENT_RANGES 52
#define MSP_SET_ADJUSTMENT_RANGE 53
// private - only to be used by the configurator, the commands are likely to change
#define MSP_CF_SERIAL_CONFIG 54
#define MSP_SET_CF_SERIAL_CONFIG 55
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
@ -213,14 +207,14 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_CONFIG" and MSP_SET_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_CONFIG 67 //in message baseflight-specific settings save
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_API_VERSION instead
#define MSP_BUILD_INFO 69 //out message build date as well as some space for future expansion
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
//
// Multwii original MSP commands
@ -657,35 +651,37 @@ static bool processOutCommand(uint8_t cmdMSP)
switch (cmdMSP) {
case MSP_API_VERSION:
// the components of this command are in an order such that future changes could be made to it without breaking clients.
// i.e. most important first.
headSerialReply(
1 + // protocol version length
API_VERSION_LENGTH +
FLIGHT_CONTROLLER_IDENTIFIER_LENGTH +
FLIGHT_CONTROLLER_VERSION_LENGTH +
BOARD_IDENTIFIER_LENGTH +
BOARD_HARDWARE_REVISION_LENGTH +
BUILD_DATE_LENGTH +
BUILD_TIME_LENGTH +
1 + // scm reference length
GIT_SHORT_REVISION_LENGTH +
1 // additional FC specific length
// no addition FC specific data yet.
API_VERSION_LENGTH
);
serialize8(MSP_PROTOCOL_VERSION);
serialize8(API_VERSION_MAJOR);
serialize8(API_VERSION_MINOR);
break;
case MSP_FC_VARIANT:
headSerialReply(FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) {
serialize8(flightControllerIdentifier[i]);
}
break;
case MSP_FC_VERSION:
headSerialReply(FLIGHT_CONTROLLER_VERSION_LENGTH);
serialize8(FC_VERSION_MAJOR);
serialize8(FC_VERSION_MINOR);
serialize8(FC_VERSION_PATCH_LEVEL);
break;
case MSP_BOARD_INFO:
headSerialReply(
BOARD_IDENTIFIER_LENGTH +
BOARD_HARDWARE_REVISION_LENGTH
);
for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) {
serialize8(boardIdentifier[i]);
}
@ -694,6 +690,14 @@ static bool processOutCommand(uint8_t cmdMSP)
#else
serialize16(0); // No other build targets currently have hardware revision detection.
#endif
break;
case MSP_BUILD_INFO:
headSerialReply(
BUILD_DATE_LENGTH +
BUILD_TIME_LENGTH +
GIT_SHORT_REVISION_LENGTH
);
for (i = 0; i < BUILD_DATE_LENGTH; i++) {
serialize8(buildDate[i]);
@ -702,11 +706,9 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(buildTime[i]);
}
serialize8(GIT_SHORT_REVISION_LENGTH);
for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) {
serialize8(shortGitRevision[i]);
}
serialize8(0); // No flight controller specific information to follow.
break;
// DEPRECATED - Use MSP_API_VERSION
@ -1052,7 +1054,7 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(masterConfig.rxConfig.rcmap[i]);
break;
case MSP_CONFIG:
case MSP_BF_CONFIG:
headSerialReply(1 + 4 + 1 + 2 + 2 + 2 + 2 + 2);
serialize8(masterConfig.mixerMode);
@ -1068,6 +1070,21 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(masterConfig.batteryConfig.currentMeterOffset);
break;
case MSP_CF_SERIAL_CONFIG:
headSerialReply(
((sizeof(uint8_t) * 2) * SERIAL_PORT_COUNT) +
(sizeof(uint32_t) * 4)
);
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
serialize8(serialPortConstraints[i].identifier);
serialize8(masterConfig.serialConfig.serial_port_scenario[i]);
}
serialize32(masterConfig.serialConfig.msp_baudrate);
serialize32(masterConfig.serialConfig.cli_baudrate);
serialize32(masterConfig.serialConfig.gps_baudrate);
serialize32(masterConfig.serialConfig.gps_passthrough_baudrate);
break;
#ifdef LED_STRIP
case MSP_LED_COLORS:
headSerialReply(CONFIGURABLE_COLOR_COUNT * 4);
@ -1080,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_LED_STRIP_CONFIG:
headSerialReply(MAX_LED_STRIP_LENGTH * 4);
headSerialReply(MAX_LED_STRIP_LENGTH * 6);
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET);
@ -1090,7 +1107,7 @@ static bool processOutCommand(uint8_t cmdMSP)
}
break;
#endif
case MSP_BUILD_INFO:
case MSP_BF_BUILD_INFO:
headSerialReply(11 + 4 + 4);
for (i = 0; i < 11; i++)
serialize8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
@ -1128,10 +1145,16 @@ static bool processInCommand(void)
magHold = read16();
break;
case MSP_SET_RAW_RC:
// FIXME need support for more than 8 channels
for (i = 0; i < 8; i++)
{
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
headSerialError(0);
} else {
for (i = 0; i < channelCount; i++)
rcData[i] = read16();
rxMspFrameRecieve();
}
}
break;
case MSP_SET_ACC_TRIM:
currentProfile->accelerometerTrims.values.pitch = read16();
@ -1368,7 +1391,7 @@ static bool processInCommand(void)
}
break;
case MSP_SET_CONFIG:
case MSP_SET_BF_CONFIG:
#ifdef USE_QUAD_MIXER_ONLY
read8(); // mixerMode ignored
@ -1389,6 +1412,24 @@ static bool processInCommand(void)
masterConfig.batteryConfig.currentMeterOffset = read16();
break;
case MSP_SET_CF_SERIAL_CONFIG:
{
uint8_t baudRateSize = (sizeof(uint32_t) * 4);
uint8_t serialPortCount = currentPort->dataSize - baudRateSize;
if (serialPortCount != SERIAL_PORT_COUNT) {
headSerialError(0);
break;
}
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
masterConfig.serialConfig.serial_port_scenario[i] = read8();
}
masterConfig.serialConfig.msp_baudrate = read32();
masterConfig.serialConfig.cli_baudrate = read32();
masterConfig.serialConfig.gps_baudrate = read32();
masterConfig.serialConfig.gps_passthrough_baudrate = read32();
}
break;
#ifdef LED_STRIP
case MSP_SET_LED_COLORS:
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
@ -1400,6 +1441,12 @@ static bool processInCommand(void)
break;
case MSP_SET_LED_STRIP_CONFIG:
{
uint8_t ledCount = currentPort->dataSize / 6;
if (ledCount != MAX_LED_STRIP_LENGTH) {
headSerialError(0);
break;
}
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
uint16_t mask;
@ -1417,6 +1464,7 @@ static bool processInCommand(void)
mask = read8();
ledConfig->xy |= CALCULATE_LED_Y(mask);
}
}
break;
#endif
case MSP_REBOOT:

View file

@ -66,6 +66,7 @@
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "config/runtime_config.h"
@ -73,8 +74,8 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#ifdef NAZE
#include "target/NAZE/hardware_revision.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
#include "build_config.h"
@ -145,12 +146,14 @@ void init(void)
SetSysClock(masterConfig.emf_avoidance);
#endif
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
detectHardwareRevision();
#endif
systemInit();
ledInit();
#ifdef SPEKTRUM_BIND
if (feature(FEATURE_RX_SERIAL)) {
switch (masterConfig.rxConfig.serialrx_provider) {
@ -169,8 +172,6 @@ void init(void)
timerInit(); // timer must be initialized before any channel is allocated
ledInit();
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioMode = Mode_Out_OD,
@ -200,7 +201,7 @@ void init(void)
spiInit(SPI2);
#endif
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
updateHardwareRevision();
#endif
@ -344,6 +345,10 @@ void init(void)
initTelemetry();
#endif
#ifdef BLACKBOX
initBlackbox();
#endif
previousTime = micros();
if (masterConfig.mixerMode == MIXER_GIMBAL) {
@ -385,6 +390,10 @@ void init(void)
#endif
}
#endif
#ifdef CJMCU
LED2_ON;
#endif
}
#ifdef SOFTSERIAL_LOOPBACK

View file

@ -67,6 +67,7 @@
#include "io/statusindicator.h"
#include "rx/msp.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "config/runtime_config.h"
#include "config/config.h"
@ -306,6 +307,15 @@ void mwDisarm(void)
}
}
#endif
#ifdef BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
finishBlackbox();
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
mspAllocateSerialPorts(&masterConfig.serialConfig);
}
}
#endif
}
}
@ -327,6 +337,16 @@ void mwArm(void)
}
}
#endif
#ifdef BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) {
mspReleasePortIfAllocated(sharedBlackboxAndMspPort);
}
startBlackbox();
}
#endif
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
return;
@ -696,9 +716,14 @@ void loop(void)
);
mixTable();
filterServos();
writeServos();
writeMotors();
#ifdef BLACKBOX
if (!cliMode && feature(FEATURE_BLACKBOX)) {
handleBlackbox();
}
#endif
}
#ifdef TELEMETRY

View file

@ -265,6 +265,10 @@ void processRxChannels(void)
{
uint8_t chan;
if (feature(FEATURE_RX_MSP)) {
return; // rcData will have already been updated by MSP_SET_RAW_RC
}
bool shouldCheckPulse = true;
if (feature(FEATURE_FAILSAFE) && feature(FEATURE_RX_PPM)) {
@ -341,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
for (c = input; *c; c++) {
s = strchr(rcChannelLetters, *c);
if (s)
if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
rxConfig->rcmap[s - rcChannelLetters] = c - input;
}
}

View file

@ -24,6 +24,8 @@
#include "drivers/gpio.h"
#include "drivers/system.h"
#include "drivers/light_led.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
@ -176,11 +178,12 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
void spektrumBind(rxConfig_t *rxConfig)
{
int i;
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
return;
}
LED1_ON;
gpio_config_t cfg = {
BIND_PIN,
Mode_Out_OD,
@ -193,16 +196,22 @@ void spektrumBind(rxConfig_t *rxConfig)
// Bind window is around 20-140ms after powerup
delay(60);
LED1_OFF;
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
LED0_OFF;
LED2_OFF;
// RX line, drive low for 120us
digitalLo(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
LED0_ON;
LED2_ON;
// RX line, drive high for 120us
digitalHi(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
}
#ifndef HARDWARE_BIND_PLUG

View file

@ -31,6 +31,7 @@ uint16_t batteryWarningVoltage;
uint16_t batteryCriticalVoltage;
uint8_t vbat = 0; // battery voltage in 0.1V steps
uint16_t vbatLatest = 0; // most recent unsmoothed raw reading from vbat adc
int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
@ -54,7 +55,7 @@ void updateBatteryVoltage(void)
uint16_t vbatSampleTotal = 0;
// store the battery voltage with some other recent battery voltage readings
vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = adcGetChannel(ADC_BATTERY);
vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = vbatLatest = adcGetChannel(ADC_BATTERY);
// calculate vbat based on the average of recent readings
for (index = 0; index < BATTERY_SAMPLE_COUNT; index++) {

View file

@ -42,6 +42,7 @@ typedef enum {
} batteryState_e;
extern uint8_t vbat;
extern uint16_t vbatLatest;
extern uint8_t batteryCellCount;
extern uint16_t batteryWarningVoltage;
extern int32_t amperage;

View file

@ -77,6 +77,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -71,6 +71,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -0,0 +1,53 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/bus_spi.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_spi_mpu6500.h"
#include "hardware_revision.h"
static const char * const hardwareRevisionNames[] = {
"Unknown",
"R1",
"R2"
};
uint8_t hardwareRevision = UNKNOWN;
void detectHardwareRevision(void)
{
if (GPIOC->IDR & GPIO_Pin_15) {
hardwareRevision = REV_2;
} else {
hardwareRevision = REV_1;
}
}
void updateHardwareRevision(void)
{
}

View file

@ -0,0 +1,27 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0,
REV_1, // Blue LED3
REV_2 // Green LED3
} cjmcuHardwareRevision_e;
extern uint8_t hardwareRevision;
void updateHardwareRevision(void);
void detectHardwareRevision(void);

View file

@ -18,16 +18,17 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define FLASH_PAGE_COUNT 64
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
#define LED0_GPIO GPIOC
#define LED0_PIN Pin_13 // PC13 (LED)
#define LED0_PIN Pin_14 // PC14 (LED)
#define LED0
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_14 // PC14 (LED)
#define LED1_PIN Pin_13 // PC13 (LED)
#define LED1
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED2_GPIO GPIOC

View file

@ -104,6 +104,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -17,7 +17,8 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considerd misleading on Naze clones like the flip32.
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
#define USE_HARDWARE_REVISION_DETECTION
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
@ -124,6 +125,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -43,6 +43,7 @@
#define SENSORS_SET (SENSOR_ACC)
#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -102,6 +102,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -87,6 +87,7 @@
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
#define BLACKBOX
#define SERIAL_RX
#define GPS
#define DISPLAY

View file

@ -56,6 +56,7 @@
#define SENSORS_SET (SENSOR_ACC)
#define BLACKBOX
#define GPS
#define LED_STRIP
#define LED_STRIP_TIMER TIM16

View file

@ -16,7 +16,7 @@
*/
#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 0 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define MW_VERSION 231