mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge remote-tracking branch 'upstream/master' into lowpass
This commit is contained in:
commit
4f0af41e79
122 changed files with 5252 additions and 1649 deletions
|
@ -74,8 +74,19 @@ Enable current monitoring using the CLI command
|
|||
feature CURRENT_METER
|
||||
```
|
||||
|
||||
Configure the current meter type using the `current_meter_type` settings as per the following table.
|
||||
|
||||
| Value | Sensor Type |
|
||||
| ----- | ---------------------- |
|
||||
| 0 | None |
|
||||
| 1 | ADC/hardware sensor |
|
||||
| 2 | Virtual sensor |
|
||||
|
||||
Configure capacity using the `battery_capacity` setting, which takes a value in mAh.
|
||||
|
||||
If you're using an OSD that expects the multiwii current meter output value, then set `multiwii_current_meter_output` to `1` (this multiplies amperage sent to MSP by 10).
|
||||
|
||||
### ADC Sensor
|
||||
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 calibration.
|
||||
|
@ -83,4 +94,23 @@ 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`.
|
||||
### Virtual Sensor
|
||||
The virtual sensor uses the throttle position to calculate as estimated current value. This is useful when a real sensor is not available. The following settings adjust the calibration.
|
||||
|
||||
| Setting | Description |
|
||||
| ----------------------------- | -------------------------------------------------------- |
|
||||
| `current_meter_scale` | The throttle scaling factor [centiamps, i.e. 1/100th A] |
|
||||
| `current_meter_offset` | The current at zero throttle [centiamps, i.e. 1/100th A] |
|
||||
|
||||
If you know your current at zero throttle (Imin) and maximum throttle(Imax) you can calculate the scaling factors using the following formulas where Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850):
|
||||
```
|
||||
current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
|
||||
current_meter_offset = Imin * 100
|
||||
```
|
||||
e.g. For a maximum current of 34.2 A and minimum current of 2.8 A with `max_throttle` = 1850
|
||||
```
|
||||
current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
|
||||
= (34.2 - 2.8) * 100000 / (850 + (850 * 850 / 50))
|
||||
= 205
|
||||
current_meter_offset = Imin * 100 = 280
|
||||
```
|
||||
|
|
|
@ -1,10 +1,12 @@
|
|||
# Board - AlienWii32
|
||||
# Board - AlienWii32 (ALIENWIIF1 and ALIENWIIF3 target)
|
||||
|
||||
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.
|
||||
The AlienWii32 is actually in prototype stage and only a few samples exist. There are two different variants and some more field testing with some users is ongoing. The information below is preliminary and will be updated as needed.
|
||||
|
||||
Here are the hardware specifications:
|
||||
|
||||
- STM32F103CBT6 MCU
|
||||
- STM32F103CBT6 MCU (ALIENWIIF1)
|
||||
- STM32F303CCT6 MCU (ALIENWIIF3)
|
||||
- optional integrated serial/ppm receiver (ALIENWIIF3 only, future enhancement)
|
||||
- MPU6050 accelerometer/gyro sensor unit
|
||||
- 8x 4.2A brushed ESCs, integrated, to run the strongest micro motors
|
||||
- extra-wide traces on the PCB, for maximum power throughput
|
||||
|
@ -21,4 +23,4 @@ Here are the hardware specifications:
|
|||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout is very similar as the NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The AlienWii32 firmware will be built with TARGET=NAZE and OPTIONS="AlienWii32". The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienWii32. The mixer can be activated with "mixer custom" in the CLI. To use the AlienWii32 in an Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the Cleanflight configurator.
|
||||
The pin layout for the ALIENWIIF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENWIIF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The AlienWii32 firmware will be built as target ALIENWIIF1 or ALIENWIIF3. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienWii32. The mixer can be activated with "mixer custom" in the CLI. To use the AlienWii32 in an Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the Cleanflight configurator.
|
||||
|
|
|
@ -10,9 +10,6 @@ If issues are found with this board please report via the [github issue tracker]
|
|||
The board has a USB port directly connected to the processor. Other boards like the Naze and Flip32
|
||||
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. 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 or failure if you try it.
|
||||
|
@ -71,13 +68,30 @@ 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 S.BUS |
|
||||
| 2 | USART3 | FLEX PORT | |
|
||||
| 3 | SoftSerial | RC connector | Pins 4 and 5 (Tx and Rx respectively) |
|
||||
| 1 | VCP | USB PORT | |
|
||||
| 2 | USART1 | MAIN PORT | Has a hardware inverter for S.BUS |
|
||||
| 3 | USART3 | FLEX PORT | |
|
||||
| 4 | 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.
|
||||
|
||||
To connect the GUI to the flight controller you need additional hardware attached to the USART1 serial port (by default).
|
||||
To connect the GUI to the flight controller you just need a USB cable to use the Virtual Com Port (VCP).
|
||||
|
||||
# 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
|
||||
|
||||
|
@ -90,6 +104,8 @@ There are two primary ways to get Cleanflight onto a CC3D board.
|
|||
|
||||
The entire flash ram on the target processor is flashed with a single image.
|
||||
|
||||
The image can be flashed by using a USB to UART adapter connected to the main port when the CC3D is put into the STM32 bootloader mode, achieved by powering on the CC3D with the SBL/3.3v pads bridged.
|
||||
|
||||
## OpenPilot Bootloader compatible image mode.
|
||||
|
||||
The initial section of flash ram on the target process is flashed with a bootloader which can then run the code in the
|
||||
|
@ -98,4 +114,3 @@ remaining area of flash ram.
|
|||
The OpenPilot bootloader code also allows the remaining section of flash to be reconfigured and re-flashed by the
|
||||
OpenPilot Ground Station (GCS) via USB without requiring a USB to uart adapter.
|
||||
|
||||
In this mode a USB to uart adapter is still required to connect to via the GUI or CLI.
|
||||
|
|
32
docs/Boards.md
Normal file
32
docs/Boards.md
Normal 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.
|
|
@ -35,4 +35,4 @@ Buzzer support on the CC3D requires that a buzzer circuit be created to which th
|
|||
PA15 is unused and not connected according to the CC3D Revision A schematic.
|
||||
Connecting to PA15 requires careful soldering.
|
||||
|
||||
See the [CC3D - buzzer circuir.pdf](Wiring/CC3D - buzzer circuir.pdf) for details.
|
||||
See the [CC3D - buzzer circuit.pdf](Wiring/CC3D - buzzer circuit.pdf) for details.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# Configuration
|
||||
|
||||
Cleanflight is configured primarilty using the Cleanflight Configurator GUI.
|
||||
Cleanflight is configured primarily 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.
|
||||
|
@ -15,7 +15,7 @@ __Due to ongoing development, the fact that the GUI cannot yet backup all your s
|
|||
|
||||
## GUI
|
||||
|
||||

|
||||

|
||||
|
||||
The GUI tool is the preferred way of configuration. The GUI tool also includes a terminal which
|
||||
can be used to interact with the CLI.
|
||||
|
|
|
@ -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.
|
||||
|
||||
|
|
|
@ -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
33
docs/Introduction.md
Normal 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
|
312
docs/LedStrip.md
312
docs/LedStrip.md
|
@ -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..
|
||||
|
||||
|
@ -51,12 +52,12 @@ uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to pow
|
|||
from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs.
|
||||
|
||||
|
||||
| Target | Pin | LED Strip | Signal |
|
||||
| --------------------- | --- | --------- | -------|
|
||||
| Naze/Olimexino | RC5 | Data In | PA6 |
|
||||
| CC3D | ??? | Data In | PB4 |
|
||||
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
||||
|
||||
| Target | Pin | LED Strip | Signal |
|
||||
| --------------------- | ---- | --------- | -------|
|
||||
| Naze/Olimexino | RC5 | Data In | PA6 |
|
||||
| CC3D | RCO5 | Data In | PB4 |
|
||||
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
||||
| Sparky | PWM5 | Data In | PA6 |
|
||||
|
||||
Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time.
|
||||
Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips
|
||||
|
@ -83,11 +84,11 @@ If you enable LED_STRIP feature and the feature is turned off again after a rebo
|
|||
|
||||
Configure the LEDs using the `led` command.
|
||||
|
||||
The `led` command takes either zero or two arguments - an zero-based led number and a pair of coordinates, direction flags and mode flags.
|
||||
The `led` command takes either zero or two arguments - an zero-based led number and a sequence which indicates pair of coordinates, direction flags and mode flags and a color.
|
||||
|
||||
If used with zero arguments it prints out the led configuration which can be copied for future reference.
|
||||
|
||||
Each led is configured using the following template: `x,y:ddd:mmm`
|
||||
Each led is configured using the following template: `x,y:ddd:mmm:cc`
|
||||
|
||||
`x` and `y` are grid coordinates of a 0 based 16x16 grid, north west is 0,0, south east is 15,15
|
||||
`ddd` specifies the directions, since an led can face in any direction it can have multiple directions. Directions are:
|
||||
|
@ -110,22 +111,29 @@ 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.
|
||||
* `C` - `C`olor.
|
||||
|
||||
`cc` specifies the color number (0 based index).
|
||||
|
||||
Example:
|
||||
|
||||
```
|
||||
led 0 0,15:SD:IAW
|
||||
led 1 15,0:ND:IAW
|
||||
led 2 0,0:ND:IAW
|
||||
led 3 0,15:SD:IAW
|
||||
led 0 0,15:SD:IAW:0
|
||||
led 1 15,0:ND:IAW:0
|
||||
led 2 0,0:ND:IAW:0
|
||||
led 3 0,15:SD:IAW:0
|
||||
led 4 7,7::C:1
|
||||
led 5 8,8::C:2
|
||||
```
|
||||
|
||||
to erase an led, and to mark the end of the chain, use `0,0::` as the second argument, like this:
|
||||
To erase an led, and to mark the end of the chain, use `0,0::` as the second argument, like this:
|
||||
|
||||
```
|
||||
led 4 0,0::
|
||||
led 4 0,0:::
|
||||
```
|
||||
|
||||
It is best to erase all LEDs that you do not have connected.
|
||||
|
||||
### Modes
|
||||
|
||||
|
@ -154,6 +162,8 @@ LEDs are set in a specific order:
|
|||
|
||||
That is, south facing LEDs have priority.
|
||||
|
||||
The mapping between modes led placement and colors is currently fixed and cannot be changed.
|
||||
|
||||
#### Indicator
|
||||
|
||||
This mode flashes LEDs that correspond to roll and pitch stick positions. i.e. they indicate the direction the craft is going to turn.
|
||||
|
@ -170,6 +180,88 @@ 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 16 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.
|
||||
|
||||
#### Solid Color
|
||||
|
||||
The mode allows you to set an LED to be permanently on and set to a specific color.
|
||||
|
||||
x,y position and directions are ignored when using this mode.
|
||||
|
||||
Other modes will override or combine with the color mode.
|
||||
|
||||
For example, to set led 0 to always use color 10 you would issue this command.
|
||||
|
||||
```
|
||||
led 0 0,0::C:10
|
||||
```
|
||||
|
||||
### Colors
|
||||
|
||||
Colors can be configured using the cli `color` command.
|
||||
|
||||
The `color` command takes either zero or two arguments - an zero-based color number and a sequence which indicates pair of hue, saturation and value (HSV).
|
||||
|
||||
See http://en.wikipedia.org/wiki/HSL_and_HSV
|
||||
|
||||
If used with zero arguments it prints out the color configuration which can be copied for future reference.
|
||||
|
||||
The default color configuration is as follows:
|
||||
|
||||
| Index | Color |
|
||||
| ----- | ----------- |
|
||||
| 0 | black |
|
||||
| 1 | white |
|
||||
| 2 | red |
|
||||
| 3 | orange |
|
||||
| 4 | yellow |
|
||||
| 5 | lime green |
|
||||
| 6 | green |
|
||||
| 7 | mint green |
|
||||
| 8 | cyan |
|
||||
| 9 | light blue |
|
||||
| 10 | blue |
|
||||
| 11 | dark violet |
|
||||
| 12 | magenta |
|
||||
| 13 | deep pink |
|
||||
| 14 | black |
|
||||
| 15 | black |
|
||||
|
||||
```
|
||||
color 0 0,0,0
|
||||
color 1 0,255,255
|
||||
color 2 0,0,255
|
||||
color 3 30,0,255
|
||||
color 4 60,0,255
|
||||
color 5 90,0,255
|
||||
color 6 120,0,255
|
||||
color 7 150,0,255
|
||||
color 8 180,0,255
|
||||
color 9 210,0,255
|
||||
color 10 240,0,255
|
||||
color 11 270,0,255
|
||||
color 12 300,0,255
|
||||
color 13 330,0,255
|
||||
color 14 0,0,0
|
||||
color 15 0,0,0
|
||||
```
|
||||
|
||||
## 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.
|
||||
|
@ -181,128 +273,150 @@ Orientation is when viewed with the front of the aircraft facing away from you a
|
|||
|
||||
The default configuration is as follows
|
||||
```
|
||||
led 0 2,2:ES:IA
|
||||
led 1 2,1:E:WF
|
||||
led 2 2,0:NE:IA
|
||||
led 3 1,0:N:F
|
||||
led 4 0,0:NW:IA
|
||||
led 5 0,1:W:WF
|
||||
led 6 0,2:SW:IA
|
||||
led 7 1,2:S:WF
|
||||
led 8 1,1:U:WF
|
||||
led 9 1,1:U:WF
|
||||
led 10 1,1:D:WF
|
||||
led 11 1,1:D:WF
|
||||
led 0 15,15:ES:IA:0
|
||||
led 1 15,8:E:WF:0
|
||||
led 2 15,7:E:WF:0
|
||||
led 3 15,0:NE:IA:0
|
||||
led 4 8,0:N:F:0
|
||||
led 5 7,0:N:F:0
|
||||
led 6 0,0:NW:IA:0
|
||||
led 7 0,7:W:WF:0
|
||||
led 8 0,8:W:WF:0
|
||||
led 9 0,15:SW:IA:0
|
||||
led 10 7,15:S:WF:0
|
||||
led 11 8,15:S:WF:0
|
||||
led 12 7,7:U:WF:0
|
||||
led 13 8,7:U:WF:0
|
||||
led 14 7,8:D:WF:0
|
||||
led 15 8,8:D:WF:0
|
||||
led 16 8,9::R:3
|
||||
led 17 9,10::R:3
|
||||
led 18 10,11::R:3
|
||||
led 19 10,12::R:3
|
||||
led 20 9,13::R:3
|
||||
led 21 8,14::R:3
|
||||
led 22 7,14::R:3
|
||||
led 23 6,13::R:3
|
||||
led 24 5,12::R:3
|
||||
led 25 5,11::R:3
|
||||
led 26 6,10::R:3
|
||||
led 27 7,9::R:3
|
||||
led 28 0,0:::0
|
||||
led 29 0,0:::0
|
||||
led 30 0,0:::0
|
||||
led 31 0,0:::0
|
||||
```
|
||||
|
||||
Which translates into the following positions:
|
||||
|
||||
```
|
||||
5 3
|
||||
\ /
|
||||
\ 4 /
|
||||
\ FRONT /
|
||||
6 | 9-12 | 2
|
||||
/ BACK \
|
||||
/ 8 \
|
||||
/ \
|
||||
7 1
|
||||
6 3
|
||||
\ /
|
||||
\ 5-4 /
|
||||
\ FRONT /
|
||||
7,8 | 12-15 | 1,2
|
||||
/ BACK \
|
||||
/ 10,11 \
|
||||
/ \
|
||||
9 0
|
||||
RING 16-27
|
||||
```
|
||||
|
||||
LEDs 1,3,5 and 7 should be placed underneath the quad, facing downwards.
|
||||
LEDs 2, 4, 6 and 8 should be positioned so the face east/north/west/south, respectively.
|
||||
LEDs 9-10 should be placed facing down, in the middle
|
||||
LEDs 11-12 should be placed facing up, in the middle
|
||||
LEDs 0,3,6 and 9 should be placed underneath the quad, facing downwards.
|
||||
LEDs 1-2, 4-5, 7-8 and 10-11 should be positioned so the face east/north/west/south, respectively.
|
||||
LEDs 12-13 should be placed facing down, in the middle
|
||||
LEDs 14-15 should be placed facing up, in the middle
|
||||
LEDs 16-17 should be placed in a ring and positioned at the rear facing south.
|
||||
|
||||
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 12 LEDs.
|
||||
|
||||
### Example 16 LED config
|
||||
|
||||
```
|
||||
led 0 15,15:SD:IA
|
||||
led 1 8,8:E:FW
|
||||
led 2 8,7:E:FW
|
||||
led 3 15,0:ND:IA
|
||||
led 4 7,7:N:FW
|
||||
led 5 8,7:N:FW
|
||||
led 6 0,0:ND:IA
|
||||
led 7 7,7:W:FW
|
||||
led 8 7,8:W:FW
|
||||
led 9 0,15:SD:IA
|
||||
led 10 7,8:S:FW
|
||||
led 11 8,8:S:FW
|
||||
led 12 7,7:D:FW
|
||||
led 13 8,7:D:FW
|
||||
led 14 7,7:U:FW
|
||||
led 15 8,7:U:FW
|
||||
led 0 15,15:SD:IA:0
|
||||
led 1 8,8:E:FW:0
|
||||
led 2 8,7:E:FW:0
|
||||
led 3 15,0:ND:IA:0
|
||||
led 4 7,7:N:FW:0
|
||||
led 5 8,7:N:FW:0
|
||||
led 6 0,0:ND:IA:0
|
||||
led 7 7,7:W:FW:0
|
||||
led 8 7,8:W:FW:0
|
||||
led 9 0,15:SD:IA:0
|
||||
led 10 7,8:S:FW:0
|
||||
led 11 8,8:S:FW:0
|
||||
led 12 7,7:D:FW:0
|
||||
led 13 8,7:D:FW:0
|
||||
led 14 7,7:U:FW:0
|
||||
led 15 8,7:U:FW:0
|
||||
```
|
||||
|
||||
Which translates into the following positions:
|
||||
|
||||
```
|
||||
7 4
|
||||
6 3
|
||||
\ /
|
||||
\ 6-5 /
|
||||
8 \ FRONT / 3
|
||||
| 13-16 |
|
||||
9 / BACK \ 2
|
||||
/ 11-12 \
|
||||
\ 5-4 /
|
||||
7 \ FRONT / 2
|
||||
| 12-15 |
|
||||
8 / BACK \ 1
|
||||
/ 10-11 \
|
||||
/ \
|
||||
10 1
|
||||
9 0
|
||||
```
|
||||
|
||||
LEDs 1,4,7 and 10 should be placed underneath the quad, facing downwards.
|
||||
LEDs 2-3, 6-5, 8-9 and 11-12 should be positioned so the face east/north/west/south, respectively.
|
||||
LEDs 13-14 should be placed facing down, in the middle
|
||||
LEDs 15-16 should be placed facing up, in the middle
|
||||
LEDs 0,3,6 and 9 should be placed underneath the quad, facing downwards.
|
||||
LEDs 1-2, 4-5, 7-8 and 10-11 should be positioned so the face east/north/west/south, respectively.
|
||||
LEDs 12-13 should be placed facing down, in the middle
|
||||
LEDs 14-15 should be placed facing up, in the middle
|
||||
|
||||
### Exmple 28 LED config
|
||||
|
||||
```
|
||||
#right rear cluster
|
||||
led 0 9,9:S:FWT
|
||||
led 1 10,10:S:FWT
|
||||
led 2 11,11:S:IA
|
||||
led 3 11,11:E:IA
|
||||
led 4 10,10:E:AT
|
||||
led 5 9,9:E:AT
|
||||
led 0 9,9:S:FWT:0
|
||||
led 1 10,10:S:FWT:0
|
||||
led 2 11,11:S:IA:0
|
||||
led 3 11,11:E:IA:0
|
||||
led 4 10,10:E:AT:0
|
||||
led 5 9,9:E:AT:0
|
||||
# right front cluster
|
||||
led 6 10,5:S:F
|
||||
led 7 11,4:S:F
|
||||
led 8 12,3:S:IA
|
||||
led 9 12,2:N:IA
|
||||
led 10 11,1:N:F
|
||||
led 11 10,0:N:F
|
||||
led 6 10,5:S:F:0
|
||||
led 7 11,4:S:F:0
|
||||
led 8 12,3:S:IA:0
|
||||
led 9 12,2:N:IA:0
|
||||
led 10 11,1:N:F:0
|
||||
led 11 10,0:N:F:0
|
||||
# center front cluster
|
||||
led 12 7,0:N:FW
|
||||
led 13 6,0:N:FW
|
||||
led 14 5,0:N:FW
|
||||
led 15 4,0:N:FW
|
||||
led 12 7,0:N:FW:0
|
||||
led 13 6,0:N:FW:0
|
||||
led 14 5,0:N:FW:0
|
||||
led 15 4,0:N:FW:0
|
||||
# left front cluster
|
||||
led 16 2,0:N:F
|
||||
led 17 1,1:N:F
|
||||
led 18 0,2:N:IA
|
||||
led 19 0,3:W:IA
|
||||
led 20 1,4:S:F
|
||||
led 21 2,5:S:F
|
||||
led 16 2,0:N:F:0
|
||||
led 17 1,1:N:F:0
|
||||
led 18 0,2:N:IA:0
|
||||
led 19 0,3:W:IA:0
|
||||
led 20 1,4:S:F:0
|
||||
led 21 2,5:S:F:0
|
||||
# left rear cluster
|
||||
led 22 2,9:W:AT
|
||||
led 23 1,10:W:AT
|
||||
led 24 0,11:W:IA
|
||||
led 25 0,11:S:IA
|
||||
led 26 1,10:S:FWT
|
||||
led 27 2,9:S:FWT
|
||||
led 22 2,9:W:AT:0
|
||||
led 23 1,10:W:AT:0
|
||||
led 24 0,11:W:IA:0
|
||||
led 25 0,11:S:IA:0
|
||||
led 26 1,10:S:FWT:0
|
||||
led 27 2,9:S:FWT:0
|
||||
```
|
||||
|
||||
```
|
||||
17-19 10-12
|
||||
20-22 \ / 7-9
|
||||
16-18 9-11
|
||||
19-21 \ / 6-8
|
||||
\ 13-16 /
|
||||
\ FRONT /
|
||||
/ BACK \
|
||||
/ \
|
||||
23-25 / \ 4-6
|
||||
26-28 1-3
|
||||
22-24 / \ 3-5
|
||||
25-27 0-2
|
||||
```
|
||||
|
||||
All LEDs should face outwards from the chassis in this configuration.
|
||||
|
|
|
@ -3,30 +3,30 @@
|
|||
Cleanflight has various modes that can be toggled on or off. Modes can be enabled/disabled by stick positions,
|
||||
auxillary receiver channels and other events such as failsafe detection.
|
||||
|
||||
| ID | Short Name | Function |
|
||||
| --- | ---------- | -------------------------------------------------------------------- |
|
||||
| 0 | ARM | Enables motors and flight stabilisation |
|
||||
| 1 | ANGLE | Legacy auto-level flight mode |
|
||||
| 2 | HORIZON | Auto-level flight mode |
|
||||
| 3 | BARO | Altitude hold mode (Requires barometer sensor) |
|
||||
| 4 | MAG | Heading lock |
|
||||
| 5 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs |
|
||||
| 6 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode |
|
||||
| 7 | CAMSTAB | Camera Stabilisation |
|
||||
| 8 | CAMTRIG | |
|
||||
| 9 | GPSHOME | Autonomous flight to HOME position |
|
||||
| 10 | GPSHOLD | Maintain the same longitude/lattitude |
|
||||
| 11 | PASSTHRU | |
|
||||
| 12 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
|
||||
| 13 | LEDMAX | |
|
||||
| 14 | LEDLOW | |
|
||||
| 15 | LLIGHTS | |
|
||||
| 16 | CALIB | |
|
||||
| 17 | GOV | |
|
||||
| 18 | OSD | Enable/Disable On-Screen-Display (OSD) |
|
||||
| 19 | TELEMETRY | Enable telemetry via switch |
|
||||
| 20 | AUTOTUNE | Autotune Pitch/Roll PIDs |
|
||||
| 21 | SONAR | Altitude hold mode (sonar sensor only) |
|
||||
| MSP ID | Short Name | Function |
|
||||
| ------- | ---------- | -------------------------------------------------------------------- |
|
||||
| 0 | ARM | Enables motors and flight stabilisation |
|
||||
| 1 | ANGLE | Legacy auto-level flight mode |
|
||||
| 2 | HORIZON | Auto-level flight mode |
|
||||
| 3 | BARO | Altitude hold mode (Requires barometer sensor) |
|
||||
| 5 | MAG | Heading lock |
|
||||
| 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs |
|
||||
| 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode |
|
||||
| 8 | CAMSTAB | Camera Stabilisation |
|
||||
| 9 | CAMTRIG | |
|
||||
| 10 | GPSHOME | Autonomous flight to HOME position |
|
||||
| 11 | GPSHOLD | Maintain the same longitude/lattitude |
|
||||
| 12 | PASSTHRU | |
|
||||
| 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
|
||||
| 14 | LEDMAX | |
|
||||
| 15 | LEDLOW | |
|
||||
| 16 | LLIGHTS | |
|
||||
| 17 | CALIB | |
|
||||
| 18 | GOV | |
|
||||
| 19 | OSD | Enable/Disable On-Screen-Display (OSD) |
|
||||
| 20 | TELEMETRY | Enable telemetry via switch |
|
||||
| 21 | AUTOTUNE | Autotune Pitch/Roll PIDs |
|
||||
| 22 | SONAR | Altitude hold mode (sonar sensor only) |
|
||||
|
||||
## Mode details
|
||||
|
||||
|
|
136
docs/PID tuning.md
Normal file
136
docs/PID tuning.md
Normal file
|
@ -0,0 +1,136 @@
|
|||
# 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 6 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=n` on the CLI tab of the Cleanflight
|
||||
Configurator, where `n` 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, "LuxFloat"
|
||||
|
||||
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.
|
||||
|
||||
It is the first PID Controller designed for 32-bit processors and not derived from MultiWii.
|
||||
|
||||
The strength of the auto-leveling correction applied during Angle mode is set by the parameter "level_angle" which
|
||||
is labeled "LEVEL Proportional" 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.
|
||||
|
||||
### PID controller 3, "MultiWii23" (default for the ALIENWIIF1 and ALIENWIIF3 targets)
|
||||
|
||||
PID Controller 3 is an direct port of the PID controller from MultiWii 2.3 and later.
|
||||
|
||||
The algorithm is handling roll and pitch differently to yaw. Users with problems on yaw authority should try this one.
|
||||
|
||||
For the ALIENWII32 targets the gyroscale is removed for even more yaw authority. This will provide best performance on very small multicopters with brushed motors.
|
||||
|
||||
### PID controller 4, "MultiWiiHybrid"
|
||||
|
||||
PID Controller 4 is an hybrid version of two MultiWii PID controllers. Roll and pitch is using the MultiWii 2.2 algorithm and yaw is using the 2.3 algorithm.
|
||||
|
||||
This PID controller was initialy implemented for testing purposes but is also performing quite well.
|
||||
|
||||
For the ALIENWII32 targets the gyroscale is removed for more yaw authority. This will provide best performance on very small multicopters with brushed motors.
|
||||
|
||||
### PID controller 5, "Harakiri"
|
||||
|
||||
PID Controller 5 is an port of the PID controller from the Harakiri firmware.
|
||||
|
||||
The algorithm is leveraging more floating point math. This PID controller also compensates for different looptimes on roll and pitch. It likely don<6F>t need retuning of the PID values when looptime is changing. Actually there are two settings hardcoded which are configurable via the GUI in Harakiri:
|
||||
|
||||
OLD_YAW 0 // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw.
|
||||
MAIN_CUT_HZ 12.0f // (default 12Hz, Range 1-50Hz)
|
||||
|
||||
The PID controller is flight tested and running well with the default PID settings. If you want do acrobatics start slowly.
|
||||
|
||||
Yaw authority is also quite good.
|
||||
|
||||
|
||||
|
17
docs/Rx.md
17
docs/Rx.md
|
@ -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
|
||||
|
||||
|
@ -61,6 +61,10 @@ 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
|
||||
|
||||
Futaba R2008SB 2.4GHz S-FHSS
|
||||
http://www.futaba-rc.com/systems/futk8100-8j/
|
||||
|
||||
|
||||
#### 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
|
||||
|
@ -82,6 +86,11 @@ These receivers are reported working:
|
|||
XG14 14ch DMSS System w/RG731BX XBus Receiver
|
||||
http://www.jramericas.com/233794/JRP00631/
|
||||
|
||||
There exist a remote receiver made for small BNF-models like the Align T-Rex 150 helicopter. The code also supports using the Align DMSS RJ01 receiver directly with the cleanflight software.
|
||||
To use this receiver you must power it with 3V from the hardware, and then connect the serial line as other serial RX receivers.
|
||||
In order for this receiver to work, you need to specify the XBUS_MODE_B_RJ01 for serialrx_provider. Note that you need to set your radio mode for XBUS "MODE B" also for this receiver to work.
|
||||
Receiver name: Align DMSS RJ01 (HER15001)
|
||||
|
||||
### SUMD
|
||||
|
||||
16 channels via serial currently supported.
|
||||
|
@ -131,7 +140,7 @@ For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as
|
|||
| SUMD | 3 |
|
||||
| SUMH | 4 |
|
||||
| XBUS_MODE_B | 5 |
|
||||
|
||||
| XBUS_MODE_B_RJ01 | 6 |
|
||||
|
||||
### PPM/PWM input filtering.
|
||||
|
||||
|
|
Before Width: | Height: | Size: 70 KiB After Width: | Height: | Size: 70 KiB |
|
@ -2,7 +2,7 @@
|
|||
|
||||
Spektrum bind with hardware bind plug support.
|
||||
|
||||
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D targets.
|
||||
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENWIIF1, ALIENWIIF3 targets.
|
||||
|
||||
## Configure the bind code
|
||||
|
||||
|
@ -46,4 +46,4 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
|
|||
|
||||
### Supported Hardware
|
||||
|
||||
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets (AlienWii32 with hardware bind plug)
|
||||
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
|
||||
|
|
|
@ -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.
|
||||
|
|
89
docs/development/Building in Ubuntu.md
Executable file
89
docs/development/Building in Ubuntu.md
Executable file
|
@ -0,0 +1,89 @@
|
|||
# Building in Ubuntu
|
||||
|
||||
Building for Ubuntu platform is remarkably easy. The only trick to understand is that the Ubuntu toolchain,
|
||||
which they are downstreaming from Debian, is not compatible with Cleanflight. We suggest that you take an
|
||||
alternative PPA from Terry Guo, found here:
|
||||
https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded
|
||||
|
||||
This PPA has several compiler versions and platforms available. For many hardware platforms (notably Naze)
|
||||
the 4.9.3 compiler will work fine. For some, older compiler 4.8 (notably Sparky) is more appropriate. We
|
||||
suggest you build with 4.9.3 first, and try to see if you can connect to the CLI or run the Configurator.
|
||||
If you cannot, please see the section below for further hints on what you might do.
|
||||
|
||||
## Setup GNU ARM Toolchain
|
||||
|
||||
Note specifically the last paragraph of Terry's PPA documentation -- Ubuntu carries its own package for
|
||||
`gcc-arm-none-eabi`, so you'll have to remove it, and then pin the one from the PPA.
|
||||
For your release, you should first remove any older pacakges (from Debian or Ubuntu directly), introduce
|
||||
Terry's PPA, and update:
|
||||
```
|
||||
sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
|
||||
sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded
|
||||
sudo apt-get update
|
||||
```
|
||||
|
||||
For Ubuntu 14.10 (current release, called Utopic Unicorn), you should pin:
|
||||
```
|
||||
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0utopic12
|
||||
```
|
||||
|
||||
For Ubuntu 14.04 (an LTS as of Q1'2015, called Trusty Tahr), you should pin:
|
||||
```
|
||||
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0trusty12
|
||||
```
|
||||
|
||||
For Ubuntu 12.04 (previous LTS, called Precise Penguin), you should pin:
|
||||
```
|
||||
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0precise12
|
||||
```
|
||||
|
||||
## Building on Ubuntu
|
||||
|
||||
After the ARM toolchain from Terry is installed, you should be able to build from source.
|
||||
```
|
||||
cd src
|
||||
git clone git@github.com:cleanflight/cleanflight.git
|
||||
cd cleanflight
|
||||
make TARGET=NAZE
|
||||
```
|
||||
|
||||
You'll see a set of files being compiled, and finally linked, yielding both an ELF and then a HEX:
|
||||
```
|
||||
...
|
||||
arm-none-eabi-size ./obj/main/cleanflight_NAZE.elf
|
||||
text data bss dec hex filename
|
||||
97164 320 11080 108564 1a814 ./obj/main/cleanflight_NAZE.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/cleanflight_NAZE.elf obj/cleanflight_NAZE.hex
|
||||
$ ls -la obj/cleanflight_NAZE.hex
|
||||
-rw-rw-r-- 1 pim pim 274258 Jan 12 21:45 obj/cleanflight_NAZE.hex
|
||||
```
|
||||
|
||||
You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file.
|
||||
|
||||
## Bricked/Bad build?
|
||||
|
||||
Users have reported that the 4.9.3 compiler for ARM produces bad builds, for example on the Sparky hardware platform.
|
||||
It is very likely that using an older compiler would be fine -- Terry happens to have also a 4.8 2014q2 build in his
|
||||
PPA - to install this, you can fetch the `.deb` directly:
|
||||
http://ppa.launchpad.net/terry.guo/gcc-arm-embedded/ubuntu/pool/main/g/gcc-arm-none-eabi/
|
||||
|
||||
and use `dpkg` to install:
|
||||
```
|
||||
sudo dpkg -i gcc-arm-none-eabi_4-8-2014q2-0saucy9_amd64.deb
|
||||
```
|
||||
|
||||
Make sure to remove `obj/` and `make clean`, before building again.
|
||||
|
||||
## Updating and rebuilding
|
||||
|
||||
Navigate to the local cleanflight repository and use the following steps to pull the latest changes and rebuild your version of cleanflight:
|
||||
|
||||
```
|
||||
cd src/cleanflight
|
||||
git reset --hard
|
||||
git pull
|
||||
make clean TARGET=NAZE
|
||||
make
|
||||
```
|
||||
|
||||
Credit goes to K.C. Budd, AKfreak for testing, and pulsar for doing the long legwork that yielded this very short document.
|
|
@ -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```.
|
||||
|
|
|
@ -16,6 +16,8 @@ This project could really do with some functional tests which test the behaviour
|
|||
|
||||
All pull requests to add/improve the testability of the code or testing methods are highly sought!
|
||||
|
||||
Note: Tests are written in C++ and linked with with firmware's C code.
|
||||
|
||||
##General principals
|
||||
|
||||
1. Name everything well.
|
||||
|
@ -26,7 +28,7 @@ All pull requests to add/improve the testability of the code or testing methods
|
|||
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.
|
||||
|
@ -48,22 +50,3 @@ You can run them on the command line to execute the tests and to see the test re
|
|||
You can also step-debug the tests in eclipse and you can use the GoogleTest test runner to make building and re-running the tests simple.
|
||||
|
||||
The tests are currently always compiled with debugging information enabled, there may be additional warnings, if you see any warnings please attempt to fix them and submit pull requests with the fixes.
|
||||
|
||||
|
||||
##TODO
|
||||
|
||||
* Test OpenLRSNG's RSSI PWM on AUX5-8.
|
||||
* Add support for UART3/4 on STM32F3.
|
||||
* Cleanup validateAndFixConfig and pwm_mapping.c to use some kind of feature/timer/io pin mapping to remove #ifdef
|
||||
* Split RX config into RC config and RX config.
|
||||
* Enabling/disabling features should not take effect until reboot since. Main loop executes and uses new flags as they are set in the cli but
|
||||
appropriate init methods will not have been called which results in undefined behaviour and could damage connected devices - this is a legacy
|
||||
problem from baseflight.
|
||||
* Solve all the naze rev4/5 HSE_VALUE == 8000000/1200000 checking, the checks should only apply to the naze32 target. See system_stm32f10x.c/SetSysClock().
|
||||
|
||||
##Known Issues
|
||||
|
||||
* Softserial RX on STM32F3 does not work. TX is fine.
|
||||
* Dynamic throttle PID does not work with new pid controller.
|
||||
* Autotune does not work yet with with new pid controller.
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue