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

Merge branch 'master' into xbus_jr01

This commit is contained in:
Stefan Grufman 2015-01-24 13:54:58 +01:00
commit 12f45b4f04
73 changed files with 1436 additions and 443 deletions

View file

@ -79,6 +79,22 @@ The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmiss
To connect the GUI to the flight controller you need additional hardware attached to the USART1 serial port (by default).
# Flex Port
The flex port will be enabled in I2C mode unless USART3 is used. You can connect external I2C sensors and displays to this port.
You cannot use USART3 and I2C at the same time.
## Flex port pinout
| Pin | Signal | Notes |
| --- | ------------------ | ----------------------- |
| 1 | GND | |
| 2 | VCC unregulated | |
| 3 | I2C SCL / UART3 TX | 3.3v level |
| 4 | I2C SDA / UART3 RX | 3.3v level (5v tolerant |
# Flashing
There are two primary ways to get Cleanflight onto a CC3D board.

32
docs/Boards.md Normal file
View file

@ -0,0 +1,32 @@
# Flight controller hardware
The current focus is geared towards flight controller hardware that use the STM32F103 and STM32F303 series processors. The core logic is separated from the hardware drivers, porting to other processors is possible.
The core set of supported flyable boards are:
* CC3D
* CJMCU
* Flip32+
* Naze32
* Sparky
* AlienWii32
Cleanflight also runs on the following developer boards:
* STM32F3Discovery
* Port103R
* EUSTM32F103RB
There is also limited support for the following boards which may be removed due to lack of users or commercial availability.
* Olimexino
* Naze32Pro
* STM32F3Discovery with Chebuzz F3 shield.
Each board has it's pros and cons, before purchasing hardware the main thing to check is if the board offers enough serial ports and input/output pins for the hardware you want to use with it and that you can use them at the same time. On some boards some features are mutually exclusive.
Please see the board-specific chapters in the manual for wiring details.
There are off-shoots (forks) of the project that support the STM32F4 processors as found on the Revo and Quanton boards.
Where applicable the chapters also provide links to other hardware that is known to work with Cleanflight, such as receivers, buzzers, etc.

View file

@ -28,7 +28,7 @@ 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:
And when:
c) the failsafe guard time specified by `failsafe_delay` has elapsed.

View file

@ -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 `gpspassthrough` 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).

33
docs/Introduction.md Normal file
View file

@ -0,0 +1,33 @@
# Cleanflight
Welcome to CleanFlight!
Cleanflight is an community project which attempts to deliver flight controller firmware and related tools.
## Primary Goals
* Community driven.
* Friendly project atmosphere.
* Focus on the needs of users.
* Great flight performance.
* Understandable and maintainable code.
## Hardware
See the flight controller hardware chapter for details.
## Software
There are two primary components, the firmware and the configuration tool. The firmware is the code that runs on the flight controller board. The GUI configuration tool (configurator) is used to configure the flight controller, it runs on Windows, OSX and Linux.
## Feedback & Contributing
We welcome all feedback. If you love it we want to hear from you, if you have problems please tell us how we could improve things so we can make it better for everyone.
If you want to contribute please see the notes here:
https://github.com/cleanflight/cleanflight#contributing
Developers should read this:
https://github.com/cleanflight/cleanflight/blob/master/CONTRIBUTING.md

View file

@ -12,6 +12,7 @@ supports the following:
* Heading/Orientation lights.
* Flight mode specific color schemes.
* Low battery warning.
* AUX operated on/off switch
The function and orientation configuration is fixed for now but later it should be able to be set via the UI or CLI..
@ -110,6 +111,7 @@ Note: It is perfectly possible to configure an LED to have all directions `NESWU
* `I` - `I`ndicator.
* `A` - `A`rmed state.
* `T` - `T`hrust state.
* `R` - `R`ing thrust state.
Example:
@ -170,6 +172,24 @@ This mode fades the LED current LED color to the previous/next color in the HSB
throttle is in the middle position the color is unaffected, thus it can be mixed with orientation colors to indicate orientation and throttle at
the same time.
#### Thrust ring state
This mode is allows you to use a 12, 16 or 24 leds ring (e.g. NeoPixel ring) for an afterburner effect. When armed the leds use the following sequences: 2 On, 4 Off, 2 On, 4 Off, and so on. The light pattern rotates clockwise as throttle increases.
A better effect is acheived when LEDs configured for thrust ring have no other functions.
LED direction and X/Y positions are irrelevant for thrust ring LED state. The order of the LEDs that have the state determines how the LED behaves.
Each LED of the ring can be a different color. The color can be selected between the 15 colors availables.
For example, led 0 is set as a `R`ing thrust state led in color 13 as follow.
```
led 0 2,2::R:13
```
LED strips and rings can be combined.
## Positioning
Cut the strip into sections as per diagrams below. When the strips are cut ensure you reconnect each output to each input with cable where the break is made.

107
docs/PID tuning.md Normal file
View file

@ -0,0 +1,107 @@
# PID tuning
Every aspect of flight dynamics is controlled by the selected "PID controller". This is an algorithm which is
responsible for reacting to your stick inputs and keeping the craft stable in the air by using the gyroscopes and/or
accelerometers (depending on your flight mode).
The "PIDs" are a set of tuning parameters which control the operation of the PID controller. The optimal PID settings
to use are different on every craft, so if you can't find someone with your exact setup who will share their settings
with you, some trial and error is required to find the best performing PID settings.
A video on how to recognise and correct different flight problems caused by PID settings is available here:
https://www.youtube.com/watch?v=YNzqTGEl2xQ
Basically, the goal of the PID controller is to bring the craft's rotation rate in all three axes to the rate that
you're commanding with your sticks. An error is computed which is the difference between your target rotation rate and
the actual one measured by the gyroscopes, and the controller tries to bring this error to zero.
The P term controls the strength of the correction that is applied to bring the craft toward the target angle or
rotation rate. If the P term is too low, the craft will be difficult to control as it won't respond quickly enough to
keep itself stable. If it is set too high, the craft will rapidly oscillate/shake as it continually overshoots its
target.
The I term corrects small, long term errors. If it is set too low, the craft's attitude will slowly drift. If it is
set too high, the craft will oscillate (but with slower oscillations than with P being set too high).
The D term attempts to increase system stability by monitoring the rate of change in the error. If the error is
changing slowly (so the P and I terms aren't having enough impact on reaching the target) the D term causes an increase
in the correction in order to reach the target sooner. If the error is rapidly converging to zero, the D term causes the
strength of the correction to be backed off in order to avoid overshooting the target.
## PID controllers
Cleanflight has three built-in PID controllers which each have different flight behavior. Each controller requires
different PID settings for best performance, so if you tune your craft using one PID controller, those settings will
likely not work well on any of the other controllers.
You can change between PID controllers by running `set pid_controller = X` on the CLI tab of the Cleanflight
Configurator, where X is the number of the controller you want to use. Please read these notes first before trying one
out!
### PID controller 0, "MultiWii" (default)
PID Controller 0 is the default controller in Cleanflight, and Cleanflight's default PID settings are tuned to be
middle-of-the-road settings for this controller. It originates from the old MultiWii PID controller from MultiWii 2.2
and earlier.
One of the quirks with this controller is that if you increase the P value for an axis, the maximum rotation rates for
that axis are lowered. Hence you need to crank up the pitch or roll rates if you have higher and higher P values.
In Horizon and Angle modes, this controller uses both the LEVEL "P" and "I" settings in order to tune the
auto-leveling corrections in a similar way to the way that P and I settings are applied to roll and yaw axes in the acro
flight modes. The LEVEL "D" term is used as a limiter to constrain the maximum correction applied by the LEVEL "P" term.
### PID controller 1, "Rewrite"
PID Controller 1 is a newer PID controller that is derived from the one in MultiWii 2.3 and later. It works better from
all accounts, and fixes some inherent problems in the way the old one worked. From reports, tuning is apparently easier
on controller 1, and it tolerates a wider range of PID values well.
Unlike controller 0, controller 1 allows the user to manipulate PID values to tune reaction and stability without
affecting yaw, roll or pitch rotation rates (which are tuned by the dedicated roll & pitch and yaw rate
settings).
In Angle mode, this controller uses the LEVEL "P" PID setting to decide how strong the auto-level correction should
be.
In Horizon mode, this controller uses the LEVEL "I" PID setting to decide how much auto-level correction should be
applied. The default Cleanflight setting for "I" will result in virtually no auto-leveling being applied, so that will
need to be increased in order to perform like PID controller 0.
The LEVEL "D" setting is not used by this controller.
### PID controller 2, "Baseflight"
PID Controller 2 is Lux's new floating point PID controller. Both controller 0 and 1 use integer arithmetic, which was
faster in the days of the slower 8-bit MultiWii controllers, but is less precise.
This controller has code that attempts to compensate for variations in the looptime, which should mean that the PIDs
don't have to be retuned when the looptime setting changes.
There were initially some problems with horizon mode, and sluggishness in acro mode, that were recently fixed by
nebbian in v1.6.0. The autotune feature does not work on this controller, so don't try to autotune it.
Even though PC2 is called "pidBaseflight" in the code, it was never in Baseflight or MultiWii. A better name might have
been pidFloatingPoint, or pidCleanflight. It is the first PID Controller designed for 32-bit processors and not derived
from MultiWii. I believe it was named pidBaseflight because it was to be the first true 32-bit processor native PID
controller, and thus the native Baseflight PC, but Timecop never accepted the code into Baseflight.
The strength of the auto-leveling correction applied during Angle mode is set by the parameter "level_angle" which
is labeled "LEVEL Integral" in the GUI. This can be used to tune the auto-leveling strength in Angle mode compared to
Horizon mode. The default is 5.0.
The strength of the auto-leveling correction applied during Horizon mode is set by the parameter "level_horizon" which
is labeled "LEVEL Integral" in the GUI. The default is 3.0, which makes the Horizon mode apply weaker self-leveling than
the Angle mode. Note: There is currently a bug in the Configurator which shows this parameter divided by 100 (so it
shows as 0.03 rather than 3.0).
The transition between self-leveling and acro behavior in Horizon mode is controlled by the "sensitivity_horizon"
parameter which is labeled "LEVEL Derivative" in the Cleanflight Configurator GUI. This sets the percentage of your
stick travel that should have self-leveling applied to it, so smaller values cause more of the stick area to fly using
only the gyros. The default is 75%
For example, at a setting of "100" for "sensitivity_horizon", 100% self-leveling strength will be applied at center
stick, 50% self-leveling will be applied at 50% stick, and no self-leveling will be applied at 100% stick. If
sensitivity is decreased to 75, 100% self-leveling will be applied at center stick, 50% will be applied at 63%
stick, and no self-leveling will be applied at 75% stick and onwards.

View file

@ -4,9 +4,9 @@ A receiver is used to receive radio control signals from your transmitter and co
There are 3 basic types of receivers:
Parallel PWM Receivers
PPM Receivers
Serial Receivers
1. Parallel PWM Receivers
2. PPM Receivers
3. Serial Receivers
## Parallel PWM Receivers

View file

@ -64,17 +64,18 @@ Only Electric Air Modules and GPS Modules are emulated, remember to enable them
Serial ports use two wires but HoTT uses a single wire so some electronics are required so that the signals don't get mixed up.
Connect as follows:
```
HoTT TX/RX -> Serial RX (connect directly)
Serial TX -> 1N4148 Diode -(| )-> HoTT TX/RX (connect via diode)
```
* HoTT TX/RX `T` -> Serial RX (connect directly)
* HoTT TX/RX `T` -> Diode `-( |)-` > Serial TX (connect via diode)
The diode should be arranged to allow the data signals to flow the right way
```
-(| )- == Diode, | indicates cathode marker.
-( |)- == Diode, | indicates cathode marker.
```
1N4148 diodes have been tested and work with the GR-24.
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.

View file

@ -38,7 +38,7 @@ Continue with the Installation and accept all autodetected dependencies.
----------
versions do matter, 4.8-2014-q2 is known to work well. Download this version from htps://launchpad.net/gcc-arm-embedded/+download - preferrebly as a ZIP-File.
versions do matter, 4.8-2014-q2 is known to work well. Download this version from https://launchpad.net/gcc-arm-embedded/+download - preferrebly as a ZIP-File.
Extract the contents of this archive to any folder of your choice, for instance ```C:\dev\gcc-arm-none-eabi-4_8-2014q2```.

View file

@ -28,7 +28,7 @@ Note: Tests are written in C++ and linked with with firmware's C code.
6. Keep methods short - it makes it easier to test.
7. Don't be afraid of moving code to a new file - it helps to reduce test dependencies.
8. Avoid noise-words in variable names, like 'data' or 'info'. Think about what you're naming and name it well. Don't be afraid to rename anything.
9. Avoid comments taht describe what the code is doing, the code should describe itself. Comments are useful however for big-picture purposes and to document content of variables.
9. Avoid comments that describe what the code is doing, the code should describe itself. Comments are useful however for big-picture purposes and to document content of variables.
10. If you need to document a variable do it at the declarion, don't copy the comment to the `extern` usage since it will lead to comment rot.
11. Seek advice from other developers - know you can always learn more.
12. Be professional - attempts at humor or slating existing code in the codebase itself is not helpful when you have to change/fix it.