@ -6,17 +6,15 @@ Clean-code version of baseflight flight-controller - flight controllers are used
This fork differs from baseflight in that it attempts to use modern software development practices which result in:
1. greater reliability through code robustness and automated testing.
1. greater reliability through code robustness and automated testing.
2. easier maintenance through code cleanliness.
3. easier to develop new features.
3. easier to develop new features.
4. easier to re-use code though code de-coupling and modularisation.
The MultiWii software, from which baseflight originated, violates many good software development best-practices. Hopefully this fork will go some way to address them. If you see any bad code in this fork please immediately raise an issue so it can be fixed, or better yet submit a pull request.
## Additional Features
Cleanflight also has additional features not found in baseflight.
* Multi-color RGB LED Strip support (each LED can be a different color using variable length WS2811 Addressable RGB strips - use for Orientation Indicators, Low Battery Warning, Flight Mode Status, etc)
There is lots of documentation here: https://github.com/cleanflight/cleanflight/tree/master/docs
There is lots of documentation here: https://github.com/cleanflight/cleanflight/tree/master/docs
If what you need is not covered then refer to the baseflight documentation. If you still can't find what you need then visit the #cleanflight on the Freenode IRC network
@ -70,7 +68,7 @@ Etiquette: Don't ask to ask and please wait around long enough for a reply - som
## Videos
There is a dedicated Cleanflight youtube channel which has progress update videos, flight demonstrations, instructions and other related videos.
There is a dedicated INAV youtube channel which has progress update videos, flight demonstrations, instructions and other related videos.
@ -26,7 +26,7 @@ Currently supported on the SPRACINGF3, STM32F3DISCOVERY, NAZE32 (including clone
## Usage
- Plug in the USB cable and connect to your board with the CleanFlight configurator.
- Plug in the USB cable and connect to your board with the INAV configurator.
- For boards without a built in USB/UART adapter, you'll need to plug an external one in. Here is how you wire up the CC3D. Plug your USB/UART adapter into the Flexi port:
@ -34,9 +34,9 @@ Currently supported on the SPRACINGF3, STM32F3DISCOVERY, NAZE32 (including clone
- Open the BlHeli Suite.
- Ensure you have selected the correct Atmel or SILABS "Cleanflight" option under the "Select ATMEL / SILABS Interface" menu option.
- Ensure you have selected the correct Atmel or SILABS "INAV" option under the "Select ATMEL / SILABS Interface" menu option.
- Ensure you have port for your external USB/UART adapter selected, if you're using one, otherwise pick the same COM port that you normally use for Cleanflight.
- Ensure you have port for your external USB/UART adapter selected, if you're using one, otherwise pick the same COM port that you normally use for INAV.
- Click "Connect" and wait for the connection to complete. If you get a COM error, hit connect again. It will probably work.
Cleanflight has a battery monitoring feature. The voltage of the main battery can be measured by the system and used to trigger a low-battery warning [buzzer](Buzzer.md), on-board status LED flashing and LED strip patterns.
INAV has a battery monitoring feature. The voltage of the main battery can be measured by the system and used to trigger a low-battery warning [buzzer](Buzzer.md), on-board status LED flashing and LED strip patterns.
Low battery warnings can:
@ -10,7 +10,7 @@ Low battery warnings can:
Minimum and maximum cell voltages can be set, and these voltages are used to auto-detect the number of cells in the battery when it is first connected.
Per-cell monitoring is not supported, as we only use one ADC to read the battery voltage.
## Supported targets
All targets support battery voltage monitoring unless status.
@ -31,12 +31,12 @@ The Naze32 has an on-board battery divider circuit; just connect your main batte
### CC3D
The CC3D has no battery divider. To use voltage monitoring, you must create a divider that gives a 3.3v
The CC3D has no battery divider. To use voltage monitoring, you must create a divider that gives a 3.3v
MAXIMUM output when the main battery is fully charged. Connect the divider output to S5_IN/PA0/RC5.
Notes:
* S5_IN/PA0/RC5 is Pin 7 on the 8 pin connector, second to last pin, on the opposite end from the
* S5_IN/PA0/RC5 is Pin 7 on the 8 pin connector, second to last pin, on the opposite end from the
GND/+5/PPM signal input.
* When battery monitoring is enabled on the CC3D, RC5 can no-longer be used for PWM input.
@ -88,7 +88,7 @@ feature CURRENT_METER
Configure the current meter type using the `current_meter_type` settings here:
| Value | Sensor Type |
| ----- | ---------------------- |
| ----- | ---------------------- |
| 0 | None |
| 1 | ADC/hardware sensor |
| 2 | Virtual sensor |
@ -111,7 +111,7 @@ Use the following settings to adjust calibration:
The virtual sensor uses the throttle position to calculate an estimated current value. This is useful when a real sensor is not available. The following settings adjust the virtual sensor calibration:
@ -34,18 +34,18 @@ can cause the flight log to drop frames and contain errors.
The Blackbox is typically used on tricopters and quadcopters. Although it will work on hexacopters and octocopters,
because these craft have more motors to record, they must transmit more data to the flight log. This can increase the
number of dropped frames. Although the browser-based log viewer supports hexacopters and octocopters, the command-line
number of dropped frames. Although the browser-based log viewer supports hexacopters and octocopters, the command-line
`blackbox_render` tool currently only supports tri- and quadcopters.
Cleanflight's `looptime` setting decides how frequently an update is saved to the flight log. The default looptime on
Cleanflight is 3500. If you're using a looptime smaller than about 2400, you may experience some dropped frames due to
INAV's `looptime` setting decides how frequently an update is saved to the flight log. The default looptime on
INAV is 2000us. If you're using a looptime smaller than about 2400, you may experience some dropped frames due to
the high required data rate. In that case you will need to reduce the sampling rate in the Blackbox settings, or
increase your logger's baudrate to 250000. See the later section on configuring the Blackbox feature for details.
## Setting up logging
First, you must enable the Blackbox feature. In the [Cleanflight Configurator][] enter the Configuration tab,
tick the "BLACKBOX" feature at the bottom of the page, and click "Save and reboot"
First, you must enable the Blackbox feature. In the [INAV Configurator][] enter the Configuration tab,
tick the "BLACKBOX" feature at the bottom of the page, and click "Save and reboot"
Now you must decide which device to store your flight logs on. You can either transmit the log data over a serial port
to an external logging device like the [OpenLog serial data logger][] to be recorded to a microSDHC card, or if you have
@ -59,9 +59,9 @@ flights to a MicroSD card.
The OpenLog ships from SparkFun with standard "OpenLog 3" firmware installed. Although this original OpenLog firmware
will work with the Blackbox, in order to reduce the number of dropped frames it should be reflashed with the
higher performance [OpenLog Blackbox firmware][]. The special Blackbox variant of the OpenLog firmware also ensures that
the OpenLog is using Cleanflight compatible settings, and defaults to 115200 baud.
the OpenLog is using INAV compatible settings, and defaults to 115200 baud.
You can find the Blackbox version of the OpenLog firmware [here](https://github.com/cleanflight/blackbox-firmware),
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
@ -95,11 +95,11 @@ First, tell the Blackbox to log using a serial port (rather than to an onboard d
Configurator's CLI tab, enter `set blackbox_device=SERIAL` to switch logging to serial, and
save.
You need to let Cleanflight know which of [your serial ports][] you connect your OpenLog to (i.e. the Blackbox port),
You need to let INAV know which of [your serial ports][] you connect your OpenLog to (i.e. the Blackbox port),
which you can do on the Configurator's Ports tab.
You should use a hardware serial port (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
rate will need to be severely reduced to compensate. Therefore the use of SoftSerial is not recommended.
When using a hardware serial port, Blackbox should be set to at least 115200 baud on that port. When using fast
@ -124,7 +124,7 @@ telemetry pins.
Pin RC3 on the side of the board is UART2's Tx pin. If Blackbox is configured on UART2, MSP can still be used on UART1
when the board is armed, which means that the Configurator will continue to work simultaneously with Blackbox logging.
Note that in `PARALLEL_PWM` mode this leaves the board with 6 input channels as RC3 and RC4 pins are used by UART2 as Tx and Rx. Cleanflight automatically shifts logical channel mapping for you when UART2 is enabled in `Ports` tab so you'll have to shift receiver pins that are connected to Naze32 pins 3 to 6 by two.
Note that in `PARALLEL_PWM` mode this leaves the board with 6 input channels as RC3 and RC4 pins are used by UART2 as Tx and Rx. INAV automatically shifts logical channel mapping for you when UART2 is enabled in `Ports` tab so you'll have to shift receiver pins that are connected to Naze32 pins 3 to 6 by two.
The OpenLog tolerates a power supply of between 3.3V and 12V. If you are powering your Naze32 with a standard 5V BEC,
then you can use a spare motor header's +5V and GND pins to power the OpenLog with.
@ -192,19 +192,19 @@ On the Configurator's CLI tab, you must enter `set blackbox_device=SPIFLASH` to
then save.
[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md
@ -20,19 +20,19 @@ Here are the hardware specifications:
- 3.3V buck-boost power converter (newer prototypes and production versions)
- battery monitoring with an LED for buzzer functionality (actualy for an ALIENWIIF3 variant)
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the INAV Configurator.
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
For more detail of the different bind modes please refer the [Spektrum Bind](Spektrum bind.md) document
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
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 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.
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 INAV configurator.
## Flashing the firmware
The AlienWii32 F1 board can be flashed like the Naze board or the related clones. All the different methods will work in the same way.
The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the Cleanflight GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the [Sparky](Board - Sparky.md) documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required.
The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the INAV GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the [Sparky](Board - Sparky.md) documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required.
@ -25,7 +25,7 @@ Both boards use the STM32F303 microcontroller and have the following features:
# Flashing
The MotoLab boards use the internal DFU USB interface on the STM32F3 microcontroller which is not compatible with the Cleanflight configurator flashing tool.
The MotoLab boards use the internal DFU USB interface on the STM32F3 microcontroller which is not compatible with the INAV configurator flashing tool.
Instead, on Windows you can use the Impulse Flashing Utility from ImpulseRC, available here:
@ -91,7 +91,7 @@ make TARGET=MOTOLAB clean
make TARGET=MOTOLAB binary
```
To completely erase the flash, create an all-zero file with this command on linux:
To completely erase the flash, create an all-zero file with this command on linux:
@ -10,7 +10,7 @@ The Sparky is a very low cost and very powerful board.
* MPU9150 I2C Acc/Gyro/Mag
* Baro
Tested with revision 1 & 2 boards.
Tested with revision 1 & 2 boards.
## TODO
@ -43,7 +43,7 @@ https://github.com/cleanflight/cleanflight/releases and store it on your Hardriv
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.."
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
@ -74,7 +74,7 @@ The status bar will show the upload progress and confirm that the upload is comp
```
Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal
Disconnect and reconnect the board from USB and continue to configure it via the INAV configurator as per normal
## Via Device Firmware Upload (DFU, USB) - Mac OS X / Linux
@ -146,7 +146,7 @@ Resetting USB to switch back to runtime mode
```
On Linux you might want to take care that the modemmanager isn't trying to use your sparky as modem getting it into bootloader mode while doing so. In doubt you probably want to uninstall it. It could also be good idea to get udev fixed. It looks like teensy did just that -> http://www.pjrc.com/teensy/49-teensy.rules (untested)
To make a full chip erase you can use a file created by
To make a full chip erase you can use a file created by
```
dd if=/dev/zero of=zero.bin bs=1 count=262144
```
@ -196,12 +196,12 @@ WARNING: Double check the output of your voltage divider using a voltmeter *befo
For a 3Cell battery divider the following circuit works:
@ -12,20 +12,20 @@ The core set of supported flyable boards are:
* Sparky
* SPRacingF3
Cleanflight also runs on the following developer boards:
INAV 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.
NOTE: Users are advised against purhasing boards that have CPUs with less than 256KB of EEPROM space - available features may be limited.
NOTE: Hardware developers should not design new boards that have CPUs with less than 256KB EEPROM space.
NOTE: Hardware developers should not design new boards that have CPUs with less than 256KB EEPROM space.
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.
@ -33,4 +33,4 @@ 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.
Where applicable the chapters also provide links to other hardware that is known to work with INAV, such as receivers, buzzers, etc.
Cleanflight supports a buzzer which is used for the following purposes:
INAV supports a buzzer which is used for the following purposes:
* Low and critical battery alarms (when battery monitoring enabled)
* Arm/disarm tones (and warning beeps while armed)
@ -12,7 +12,7 @@ Cleanflight supports a buzzer which is used for the following purposes:
If the arm/disarm is via the control stick, holding the stick in the disarm position will sound a repeating tone. This can be used as a lost-model locator.
Three beeps immediately after powering the board means that the gyroscope calibration has completed successfully. Cleanflight calibrates the gyro automatically upon every power-up. It is important that the copter stay still on the ground until the three beeps sound, so that gyro calibration isn't thrown off. If you move the copter significantly during calibration, Cleanflight will detect this, and will automatically re-start the calibration once the copter is still again. This will delay the "three beeps" tone. If you move the copter just a little bit, the gyro calibration may be incorrect, and the copter may not fly correctly. In this case, the gyro calibration can be performed manually via [stick command](Controls.md), or you may simply power cycle the board.
Three beeps immediately after powering the board means that the gyroscope calibration has completed successfully. INAV calibrates the gyro automatically upon every power-up. It is important that the copter stay still on the ground until the three beeps sound, so that gyro calibration isn't thrown off. If you move the copter significantly during calibration, INAV will detect this, and will automatically re-start the calibration once the copter is still again. This will delay the "three beeps" tone. If you move the copter just a little bit, the gyro calibration may be incorrect, and the copter may not fly correctly. In this case, the gyro calibration can be performed manually via [stick command](Controls.md), or you may simply power cycle the board.
There is a special arming tone used if a GPS fix has been attained, and there's a "ready" tone sounded after a GPS fix has been attained (only happens once). The tone sounded via the TX-AUX-switch will count out the number of satellites (if GPS fix).
@ -24,7 +24,7 @@ Buzzer is enabled by default on platforms that have buzzer connections.
Buzzer tone sequences (square wave generation) are made so that : 1st, 3rd, 5th, .. are the delays how long the beeper is on and 2nd, 4th, 6th, .. are the delays how long beeper is off. Delays are in milliseconds/10 (i.e., 5 => 50ms).
Sequences available in Cleanflight v1.9 and above are :
Cleanflight has a command line interface (CLI) that can be used to change settings and configure the FC.
INAV has a command line interface (CLI) that can be used to change settings and configure the FC.
## Accessing the CLI.
@ -251,5 +251,5 @@ Re-apply any new defaults as desired.
| `yaw_p_limit` | Limiter for yaw P term. This parameter is only affecting PID controller MW23. To disable set to 500 (actual default). | 100 | 500 | 500 | Profile | UINT16 |
| `mag_hold_rate_limit` | This setting limits yaw rotation rate that MAG_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when MAG_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes.
| `mag_hold_rate_limit` | This setting limits yaw rotation rate that MAG_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when MAG_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes.
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.
[Cleanflight Configurator on Chrome store](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb)
[INAV 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.
INAV can also be configured by a command line interface.
See the CLI section of the documentation for more details.
Cleanflight supports displays to provide information to you about your aircraft and cleanflight state.
INAV 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.
@ -29,7 +29,7 @@ before they work. Choose wisely!
Links to displays:
* [banggood.com](http://www.banggood.com/0_96-Inch-4Pin-White-IIC-I2C-OLED-Display-Module-12864-LED-For-Arduino-p-958196.html) 0.96 Inch 4Pin White IIC I2C OLED Display Module 12864 LED For Arduino
* [banggood.com](http://www.banggood.com/0_96-Inch-4Pin-White-IIC-I2C-OLED-Display-Module-12864-LED-For-Arduino-p-958196.html) 0.96 Inch 4Pin White IIC I2C OLED Display Module 12864 LED For Arduino
* [banggood.com](http://www.banggood.com/0_96-Inch-4Pin-IIC-I2C-Blue-OLED-Display-Module-For-Arduino-p-969147.html) 0.96 Inch 4Pin IIC I2C Blue OLED Display Module For Arduino
This is a step-by-step guide that can help a person that has never used Cleanflight before set up a flight controller and the aircraft around it for flight. Basic RC knowledge is required, though. A total beginner should first familiarize themselves with concepts and techniques of RC before using this (e.g. basic controls, soldering, transmitter operation etc). One could use [RCGroups](http://www.rcgroups.com/forums/index.php) and/or [the Youtube show FliteTest](https://www.youtube.com/user/flitetest) for this.
This is a step-by-step guide that can help a person that has never used INAV before set up a flight controller and the aircraft around it for flight. Basic RC knowledge is required, though. A total beginner should first familiarize themselves with concepts and techniques of RC before using this (e.g. basic controls, soldering, transmitter operation etc). One could use [RCGroups](http://www.rcgroups.com/forums/index.php) and/or [the Youtube show FliteTest](https://www.youtube.com/user/flitetest) for this.
DISCLAIMER: This documents is a work in progress. We cannot guarantee the safety or success of your project. At this point the document is only meant to be a helping guide, not an authoritative checklist of everything you should do to be safe and successful. Always exercise common sense, critical thinking and caution.
Read the [Introduction](Introduction.md) chapter for an overview of Cleanflight and how the community works.
Read the [Introduction](Introduction.md) chapter for an overview of INAV and how the community works.
## Hardware
NOTE: Flight Controllers are typically equipped with accelerometers. These devices are sensitive to shocks. When the device is not yet installed to an aircraft, it has very little mass by itself. If you drop or bump the controller, a big force will be applied on its accelerometers, which could potentially damage them. Bottom line: Handle the board very carefully until it's installed on an aircraft!
For an overview of the hardware Cleanflight (hereby CF) can run on, see [Boards.md](Boards.md). For information about specific boards, see the board specific documentation.
For an overview of the hardware INAV (hereby CF) can run on, see [Boards.md](Boards.md). For information about specific boards, see the board specific documentation.
* Assuming that you have a flight controller board (hereby FC) in hand, you should first read through the manual that it came with. You can skip the details about software setup, as we'll cover that here.
* Decide how you'll connect your receiver by reading the [receiver](Rx.md) chapter, and how many pins you need on the outputs (to connect ESCs and servos) by reading about [Mixers](Mixer.md).
* Decide how you'll connect your receiver by reading the [receiver](Rx.md) chapter, and how many pins you need on the outputs (to connect ESCs and servos) by reading about [Mixers](Mixer.md).
* If you're interested in monitoring your flight battery with CF, see [Battery Monitoring](Battery.md).
@ -32,11 +32,11 @@ For an overview of the hardware Cleanflight (hereby CF) can run on, see [Boards.
## Software setup
Now that your board has pins on it, you are ready to connect it to your PC and flash it with CF. Install the Chromium browser or Google Chrome to your PC, if you don't have it already, add the [Cleanflight Configurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb) to it, and start it.
Now that your board has pins on it, you are ready to connect it to your PC and flash it with CF. Install the Chromium browser or Google Chrome to your PC, if you don't have it already, add the [INAV Configurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb) to it, and start it.
Then follow these instructions for [Installation](Installation.md) of the firmware to the FC.
## Cleanflight Configuration
## INAV Configuration
Your FC should now be running CF, and you should be able to connect to it using the Configurator. If that is not the case, please go back to the previous sections and follow the steps carefully.
@ -49,7 +49,7 @@ Now, there are two ways to [configure CF](Configuration.md); via the Configurat
* On your PC, connect to the Configurator, and go to the first tab. Check that the board animation is moving properly when you move the actual board. Do an accelerometer calibration.
* Configuration tab: Select your aircraft configuration (e.g. Quad X), and go through each option in the tab to check if relevant for you.
* Configuration tab: Select your aircraft configuration (e.g. Quad X), and go through each option in the tab to check if relevant for you.
* E.g. you may want to enable ONESHOT125 for Oneshot-capable ESCs.
* You may need RX_PPM if you're using an RC Receiver with PPM output etc.
@ -64,11 +64,11 @@ Now, there are two ways to [configure CF](Configuration.md); via the Configurat
* Minimum Command - This is the "idle" signal level that will be sent to the ESCs when the craft is disarmed, which should not cause the motors to spin. A typical value would be 1000.
* Finally, click Save and Reboot.
* Receiver tab:
* Check that the channel inputs move according to your Tx inputs.
* Receiver tab:
* Check that the channel inputs move according to your Tx inputs.
* Check that the Channel map is correct along with the RSSI Channel, if you use that.
* Verify the range of each channel goes from ~1000 to ~2000. See also [controls](Controls.md). and `rx_min_usec` and `rx_max_usec`.
* You can also set EXPO here instead of your Tx.
* You can also set EXPO here instead of your Tx.
* Click Save!
* Modes tab: Setup the desired modes. See the [modes](Modes.md) chapter for what each mode does, but for the beginning you mainly need HORIZON, if any.
@ -105,4 +105,3 @@ Some advanced configurations and features are documented in the following pages,
* [Telemetry](Telemetry.md)
* [Using a Display](Display.md)
* [Using a LED strip](LedStrip.md)
* [Migrating from baseflight](Migrating from baseflight.md)
GPS features in Cleanflight are experimental. Please share your findings with the developers.
GPS features in INAV are experimental. Please share your findings with the developers.
GPS works best if the GPS receiver is mounted above and away from other sources of interference.
@ -19,7 +19,7 @@ Enable the GPS from the CLI as follows:
1. connect your GPS to the serial port configured for GPS.
1. save and reboot.
Note: GPS packet loss has been observed at 115200. Try using 57600 if you experience this.
Note: GPS packet loss has been observed at 115200. Try using 38400 is enough in most of the cases.
For the connections step check the Board documentation for pins and port numbers.
@ -87,7 +87,7 @@ Set `Protocol Out` to `0+1`
Set `Buadrate` to `57600``115200`
Press `Send`
This will immediatly "break" communication to the GPS. Since you haven't saved the new baudrate setting to the non-volatile memory you need to change the baudrate you communicate to the GPS without resetting the GPS. So `Disconnect`, Change baud rate to match, then `Connect`.
This will immediatly "break" communication to the GPS. Since you haven't saved the new baudrate setting to the non-volatile memory you need to change the baudrate you communicate to the GPS without resetting the GPS. So `Disconnect`, Change baud rate to match, then `Connect`.
Click on `PRT` in the Configuration view again and inspect the packet console to make sure messages are being sent and acknowledged.
@ -131,7 +131,7 @@ Select `Save current configuration` and click `Send`.
### UBlox Navigation model
If GPS auto configuration is used Cleanflight will use `Airborne<1G` when `gps_nav_model=LOW_G` and `Airborne<4G` when `gps_nav_model=HIGH_G`.
If GPS auto configuration is used INAV will use `Airborne<1G` when `gps_nav_model=LOW_G` and `Airborne<4G` when `gps_nav_model=HIGH_G`.
From the UBlox documentation:
@ -141,8 +141,8 @@ From the UBlox documentation:
## Hardware
There are many GPS receivers available on the market.
Below are some examples of user-tested hardware.
There are many GPS receivers available on the market.
With Cleanflight it's possible to make adjustments to various settings by using AUX channels from your transmitter while the aircraft is flying.
With INAV it's possible to make adjustments to various settings by using AUX channels from your transmitter while the aircraft is flying.
## Warning
@ -12,7 +12,7 @@ Changing settings during flight can make your aircraft unstable and crash if you
* Make small adjustments and fly carefully to test your adjustment.
* Give yourself enough flying space and time to adjust to how your changes affect the behaviour of the aircraft.
* Remember to set adjustment channel switches/pots to the center position before powering on your TX and your aircraft.
* If possible configure switch warnings on your transitter for dedicated adjustment switches.
* If possible configure switch warnings on your transitter for dedicated adjustment switches.
* A momentary 3 position switch is the best choice of switch for this - i.e. one that re-centers itself when you let go of it.
## Overview
@ -51,7 +51,7 @@ When the switch is returned to the center position the value will not be increas
Each time you can press the switch high/low and then return it to the middle the value will change at least once, you do not have to wait before pressing the switch again if you want to increase/decrease at a faster rate. While the adjustment switch held is high/low, the adjustment function applies and increases/decreases the value being adjusted twice a second and the flight controller will beep shorter/longer, respectively. The system works similar to how a keyboard repeat delay works.
Hint: With OpenTX transmitters you can combine two momentary OFF-ON switches to control a single channel. You could make it so that a momentary switch on the left of your transmitter decreases the value and a momentary switch on the right increases the value. Experiment with your mixer!
## Configuration
@ -62,7 +62,7 @@ The CLI command `adjrange` is used to configure adjustment ranges.
Show the current ranges using:
`adjrange`
`adjrange`
Configure a range using:
@ -74,8 +74,8 @@ Configure a range using:
| -------- | ----- |-------- |
| Index | 0 - 11 | Select the adjustment range to configure |
| Slot | 0 - 3 | Select the adjustment slot to use |
| Range Channel | 0 based index, AUX1 = 0, AUX2 = 1 | The AUX channel to use to select an adjustment for a switch/pot |
| Range Start | 900 - 2100. Steps of 25, e.g. 900, 925, 950... | Start of range |
| Range Channel | 0 based index, AUX1 = 0, AUX2 = 1 | The AUX channel to use to select an adjustment for a switch/pot |
| Range Start | 900 - 2100. Steps of 25, e.g. 900, 925, 950... | Start of range |
| Range End | 900 - 2100 | End of range |
| Adjustment function | 0 - 11 | See Adjustment function table |
| Adjustment channel | 0 based index, AUX1 = 0, AUX2 = 1 | The channel that is controlled by a 3 Position switch/Pot |
@ -86,7 +86,7 @@ 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 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.
This is a generic procedure to flash a board using the configurator. The configurator does not yet support all boards, so please check the documentation corresponding to your board before proceeding.
Make sure you have the [Cleanflight Configurator](https://github.com/cleanflight/cleanflight-configurator) installed, then:
Make sure you have the [INAV Configurator](https://github.com/iNavFlight/inav-configurator) installed, then:
* Connect the flight controller to the PC.
* Start the Cleanflight Configurator.
* Start the INAV Configurator.
* Click on "Disconnect" if the configurator connected to the board automatically.
* Click on the "Firmware Flasher" tab.
* Make sure you have internet connectivity and click on the "Load Firmware [Online]" button.
* Click on the "Choose a Firmware / Board" dropdown menu, and select the latest stable version for your flight controller.
* IMPORTANT: Read and understand the release notes that are displayed. When upgrading review all release notes since your current firmware.
* If this is the first time Cleanflight is flashed to the board, tick the "Full Chip Erase" checkbox.
* If this is the first time INAV is flashed to the board, tick the "Full Chip Erase" checkbox.
* Connect the flight controller board to the PC. Ensure the correct serial port is selected.
* Click on the "Flash Firmware" button and hold still (do not breathe, too).
* When the progress bar becomes green and reads "Programming: SUCCESSFUL" you are done!
Cleanflight supports the use of addressable LED strips. Addressable LED strips allow each LED in the strip to
INAV 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
require that all the LEDs in the strip show the same color.
@ -234,7 +234,7 @@ the same time. Thrust should normally be combined with Color or Mode/Orientatio
#### 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.
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.
@ -242,7 +242,7 @@ LED direction and X/Y positions are irrelevant for thrust ring LED state. The o
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.
For example, led 0 is set as a `R`ing thrust state led in color 13 as follow.
```
led 0 2,2::R:13
@ -258,7 +258,7 @@ 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.
For example, to set led 0 to always use color 10 you would issue this command.
```
led 0 0,0::C:10
@ -407,13 +407,13 @@ Which translates into the following positions:
```
6 3
\ /
\ 5-4 /
\ /
\ 5-4 /
7 \ FRONT / 2
| 12-15 |
| 12-15 |
8 / BACK \ 1
/ 10-11 \
/ \
/ \
9 0
```
@ -421,7 +421,7 @@ 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
**First ensure your main flight battery is disconnected or your props are off!**
Before flashing with cleanflight, dump your configs for each profile via the CLI and save to a text file.
```
profile 0
dump
profile 1
dump
profile 2
dump
```
Then after flashing cleanflight paste the output from each dump command into the cli, switching profiles as you go.
You'll note that some commands are not recognised by cleanflight when you do this. For the commands that are not recognised look
up the new configuration options and choose appropriate values for the settings. See below for a list of differences.
Once you've done this for the first profile, save the config. Then verify your config is OK, e.g. features serial ports, etc.
When you've verified the first profile is OK repeat for the other profiles.
It's also advisable to take screenshots of your AUX settings from baseflight configurator and then after re-applying the settings
verify your aux config is correct - aux settings are not backwards compatible.
## CLI command differences from baseflight
In general all CLI commands use underscore characters to separate words for consistency. In baseflight the format of CLI commands is somewhat haphazard.
### gps_baudrate
reason: new serial port configuration.
See `serial` command.
### gps_type
reason: renamed to `gps_provider` for consistency
### serialrx_type
reason: renamed to `serialrx_provider` for consistency
### rssi_aux_channel
reason: renamed to `rssi_channel` for improved functionality
Cleanflight supports using any RX channel for rssi. Baseflight only supports AUX1 to 4.
In Cleanflight a value of 0 disables the feature, a higher value indicates the channel number to read RSSI information from.
Example: to use RSSI on AUX1 in Cleanflight use `set rssi_channel = 5`, since 5 is the first AUX channel (this is equivalent to `set rssi_aux_channel = 1` in Baseflight).
### failsafe_detect_threshold
reason: improved functionality
See `rx_min_usec` and `rx_max_usec` in Failsafe documentation.
### emfavoidance
reason: renamed to `emf_avoidance` for consistency
### yawrate
reason: renamed to `yaw_rate` for consistency
### yawdeadband
reason: renamed to `yaw_deadband` for consistency
### midrc
reason: renamed to `mid_rc` for consistency
### mincheck
reason: renamed to `min_check` for consistency
### maxcheck
reason: renamed to `max_check` for consistency
### minthrottle
reason: renamed to `min_throttle` for consistency
### maxthrottle
reason: renamed to `max_throttle` for consistency
### mincommand
reason: renamed to `min_command` for consistency
### deadband3d_low
reason: renamed to `3d_deadband_low` for consistency
### deadband3d_high
reason: renamed to `3d_deadband_high` for consistency
### deadband3d_throttle
reason: renamed to `3d_deadband_throttle` for consistency
### neutral3d
reason: renamed to `3d_neutral` for consistency
### alt_hold_throttle_neutral
reason: renamed to `alt_hold_deadband` for consistency
### gimbal_flags
reason: seperation of features.
see `gimbal_mode` and `CHANNEL_FORWARDING` feature
Cleanflight supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft.
INAV supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft.
## Configuration
@ -44,14 +44,14 @@ You can also use the Command Line Interface (CLI) to set the mixer type:
## Servo configuration
The cli `servo` command defines the settings for the servo outputs.
The cli `servo` command defines the settings for the servo outputs.
The cli mixer `smix` command controllers how the mixer maps internal FC data (RC input, PID stabilisation output, channel forwarding, etc) to servo outputs.
## Servo filtering
A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example.
### Configuration
### Configuration
Currently it can only be configured via the CLI:
@ -75,19 +75,19 @@ One method for tuning the filter cutoff is as follows:
4. If the oscillations are dampened within roughly a second or are no longer present, then you are done. Be sure to run `save`.
## Custom Motor Mixing
## Custom Motor Mixing
Custom motor mixing allows for completely customized motor configurations. Each motor must be defined with a custom mixing table for that motor. The mix must reflect how close each motor is with reference to the CG (Center of Gravity) of the flight controller. A motor closer to the CG of the flight controller will need to travel less distance than a motor further away.
Steps to configure custom mixer in the CLI:
1. Use `mixer custom` to enable the custom mixing.
2. Use `mmix reset` to erase the any existing custom mixing.
3. Issue a `mmix` statement for each motor.
2. Use `mmix reset` to erase the any existing custom mixing.
3. Issue a `mmix` statement for each motor.
The mmix statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
The mmix statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
| Mixing table parameter | Definition |
| Mixing table parameter | Definition |
| ---------------------- | ---------- |
| n | Motor ordering number |
| THROTTLE | All motors that are used in this configuration are set to 1.0. Unused set to 0.0. |
@ -95,7 +95,7 @@ The mmix statement has the following syntax: `mmix n THROTTLE ROLL PITCH YAW`
| PITCH | Indicates the pitch authority this motor has over the flight controller. Also accepts values nominally from 1.0 to -1.0. |
| YAW | Indicates the direction of the motor rotation in relationship with the flight controller. 1.0 = CCW -1.0 = CW. |
Note: the `mmix` command may show a motor mix that is not active, custom motor mixes are only active for models that use custom mixers.
Note: the `mmix` command may show a motor mix that is not active, custom motor mixes are only active for models that use custom mixers.
## Custom Servo Mixing
@ -105,11 +105,11 @@ Custom servo mixing rules can be applied to each servo. Rules are applied in th
| 6 | THROTTLE (Based ONLY on the first motor output) |
| 6 | THROTTLE (Based ONLY on the first motor output) |
| 7 | FLAPS |
@ -130,7 +130,7 @@ Custom servo mixing rules can be applied to each servo. Rules are applied in th
| 12 | GIMBAL PITCH |
| 13 | GIMBAL ROLL |
Note: the `smix` command may show a servo mix that is not active, custom servo mixes are only active for models that use custom mixers.
Note: the `smix` command may show a servo mix that is not active, custom servo mixes are only active for models that use custom mixers.
## Servo Reversing
@ -144,8 +144,8 @@ i.e. when mixing rudder servo slot (`5`) using Stabilised YAW input source (`2`)
`smix reverse` is a per-profile setting. So ensure you configure it for your profiles as required.
### Example 1: A KK2.0 wired motor setup
Here's an example of a X configuration quad, but the motors are still wired using the KK board motor numbering scheme.
### Example 1: A KK2.0 wired motor setup
Here's an example of a X configuration quad, but the motors are still wired using the KK board motor numbering scheme.
```
KK2.0 Motor Layout
@ -164,28 +164,28 @@ KK2.0 Motor Layout
5. Use `mmix 2 1.0, -1.0, 1.0, -1.0` for the Rear Right motor. It has negative roll, provides positive pitch when the speed is increased and turns CW.
6. Use `mmix 3 1.0, 1.0, 1.0, 1.0` for the Rear Left motor. Increasing motor speed imparts positive roll, positive pitch and turns CCW.
### Example 2: A HEX-U Copter
### Example 2: A HEX-U Copter
Here is an example of a U-shaped hex; probably good for herding giraffes in the Sahara. Because the 1 and 6 motors are closer to the roll axis, they impart much less force than the motors mounted twice as far from the FC CG. The effect they have on pitch is the same as the forward motors because they are the same distance from the FC CG. The 2 and 5 motors do not contribute anything to pitch because speeding them up and slowing them down has no effect on the forward/back pitch of the FC.
Here is an example of a U-shaped hex; probably good for herding giraffes in the Sahara. Because the 1 and 6 motors are closer to the roll axis, they impart much less force than the motors mounted twice as far from the FC CG. The effect they have on pitch is the same as the forward motors because they are the same distance from the FC CG. The 2 and 5 motors do not contribute anything to pitch because speeding them up and slowing them down has no effect on the forward/back pitch of the FC.
```
```
HEX6-U
.4........3.
.4........3.
............
.5...FC...2.
.5...FC...2.
............
...6....1...
```
|Command| Roll | Pitch | Yaw |
| ----- | ---- | ----- | --- |
| ----- | ---- | ----- | --- |
| Use `mmix 0 1.0, -0.5, 1.0, -1.0` | half negative | full positive | CW |
| Use `mmix 1 1.0, -1.0, 0.0, 1.0` | full negative | none | CCW |
| Use `mmix 2 1.0, -1.0, -1.0, -1.0` | full negative | full negative | CW |
| Use `mmix 3 1.0, 1.0, -1.0, 1.0` | full positive | full negative | CCW |
| Use `mmix 4 1.0, 1.0, 0.0, -1.0` | full positive | none | CW |
| Use `mmix 5 1.0, 0.5, 1.0, 1.0` | half positive | full positive | CCW |
| Use `mmix 1 1.0, -1.0, 0.0, 1.0` | full negative | none | CCW |
| Use `mmix 2 1.0, -1.0, -1.0, -1.0` | full negative | full negative | CW |
| Use `mmix 3 1.0, 1.0, -1.0, 1.0` | full positive | full negative | CCW |
| Use `mmix 4 1.0, 1.0, 0.0, -1.0` | full positive | none | CW |
| Use `mmix 5 1.0, 0.5, 1.0, 1.0` | half positive | full positive | CCW |
### Example 3: Custom tricopter
@ -210,7 +210,7 @@ smix reverse 5 2 r
Here is an example of a custom twin engine plane with [Differential Thrust](http://rcvehicles.about.com/od/rcairplanes/ss/RCAirplaneBasic.htm#step8)
Motors take the first 2 pins, the servos take pins as indicated in the [Servo slot] chart above.
Settings bellow have motor yaw influence at "0.3", you can change this nuber to have more or less differential thrust over the two motors.
Note: You can look at the Motors tab in [Cleanflight Cofigurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en) to see motor and servo outputs.
Note: You can look at the Motors tab in [INAV Cofigurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en) to see motor and servo outputs.
Cleanflight has various modes that can be toggled on or off. Modes can be enabled/disabled by stick positions,
INAV 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.
| MSP ID | CLI ID | Short Name | Function |
@ -35,7 +35,7 @@ auxillary receiver channels and other events such as failsafe detection.
In this mode, the "head" of the multicopter is always pointing to the same direction as when the feature was activated. This means that when the multicopter rotates around the Z axis (yaw), the controls will always respond according the same "head" direction.
With this mode it is easier to control the multicopter, even fly it with the physical head towards you since the controls always respond the same. This is a friendly mode to new users of multicopters and can prevent losing the control when you don't know the head direction.
With this mode it is easier to control the multicopter, even fly it with the physical head towards you since the controls always respond the same. This is a friendly mode to new users of multicopters and can prevent losing the control when you don't know the head direction.
### GPS Return To Home
@ -73,7 +73,7 @@ When a channel is within a specifed range the corresponding mode is enabled.
Use the GUI configuration tool to allow easy configuration when channel.
### CLI
### CLI
There is a CLI command, `aux` that allows auxillary configuration. It takes 5 arguments as follows:
@ -88,10 +88,9 @@ If the low and high position are the same then the values are ignored.
e.g.
Configure AUX range slot 0 to enable ARM when AUX1 is withing 1700 and 2100.
```
aux 0 0 0 1700 2100
```
You can display the AUX configuration by using the `aux` command with no arguments.
@ -61,15 +61,15 @@ If you are getting oscillations starting at say 3/4 throttle, set tpa breakpoint
## PID controllers
Cleanflight has 3 built-in PID controllers which each have different flight behavior. Each controller requires
INAV has 3 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
You can change between PID controllers by running `set pid_controller=x` on the CLI tab of the INAV
Configurator, where `x` is the controller you want to use. Please read these notes first before trying one
out.
Note that older Cleanflight versions had 6 pid controllers, experimental and old ones were removed in 1.11.0 / API 1.14.0.
Note that older INAV versions had 6 pid controllers, experimental and old ones were removed in 1.11.0 / API 1.14.0.
### PID controller "MW23"
@ -77,14 +77,14 @@ This PID Controller is a direct port of the PID controller from MultiWii 2.3 and
The algorithm is handling roll and pitch differently to yaw. Users with problems on yaw authority should try this one.
In Horizon and Angle modes, this controller uses both the LEVEL "P" and "I" settings in order to tune the
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 "MWREWRITE"
This 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,
all accounts, and fixes some inherent problems in the way the old one worked. From reports, tuning is apparently easier,
and it tolerates a wider range of PID values well.
In Angle mode, this controller uses the LEVEL "P" PID setting to decide how strong the auto-level correction should
@ -98,7 +98,7 @@ This is a new floating point based PID controller. MW23 and MWREWRITE use intege
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.
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.
@ -115,9 +115,9 @@ the Angle mode. Note: There is currently a bug in the Configurator which shows t
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
parameter which is labeled "LEVEL Derivative" in the INAV 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%
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
@ -128,7 +128,7 @@ stick, and no self-leveling will be applied at 75% stick and onwards.
### RC Rate
An overall multiplier on the RC stick inputs for pitch, rol;, and yaw.
An overall multiplier on the RC stick inputs for pitch, rol;, and yaw.
On PID Controller MW23 can be used to set the "feel" around center stick for small control movements. (RC Expo also affects this).For PID Controllers MWREWRITE and LUX, this basically sets the baseline stick sensitivity
Cleanflight has enhanced serial port flexibility but configuration is slightly more complex as a result.
INAV 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).
INAV 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
constraints.
@ -23,17 +23,17 @@ These are sometimes referred to as FTDI boards. FTDI is just a common manufactu
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.
Examples:
* [FT232RL FTDI USB To TTL Serial Converter Adapter](http://www.banggood.com/FT232RL-FTDI-USB-To-TTL-Serial-Converter-Adapter-Module-For-Arduino-p-917226.html)
* [USB To TTL / COM Converter Module buildin-in CP2102](http://www.banggood.com/Wholesale-USB-To-TTL-Or-COM-Converter-Module-Buildin-in-CP2102-New-p-27989.html)
Both SoftSerial and UART ports can be connected to your computer via USB to UART converter boards.
Both SoftSerial and UART ports can be connected to your computer via USB to UART converter boards.
## Serial Configuration
Serial port configuration is best done via the configurator.
Configure serial ports first, then enable/disable features that use the ports. To configure SoftSerial ports the SOFTSERIAL feature must be also be enabled.
Configure serial ports first, then enable/disable features that use the ports. To configure SoftSerial ports the SOFTSERIAL feature must be also be enabled.
### Constraints
@ -59,7 +59,7 @@ You can use the CLI for configuration but the commands are reserved for develope
The `serial` CLI command takes 6 arguments.
1. Identifier
1. Function bitmask (see serialPortFunction_e in the source)
1. Function bitmask (see serialPortFunction_e in the source)
1. MSP baud rate
1. GPS baud rate
1. Telemetry baud rate (auto baud allowed)
@ -80,4 +80,3 @@ The allowable baud rates are as follows:
The bitmapDecompress function in Cleanflight is currently designed to work with RLE compressed monochrome bitmaps.
The bitmapDecompress function in INAV is currently designed to work with RLE compressed monochrome bitmaps.
## Image format
@ -14,7 +14,7 @@ Example Photoshop new image settings:
## Compression and HEX conversion
Your new bitmap file will need to be converted to run-length encoding compressed hexidecimal. The [Gabotronics Image to HEX Converter v1.03](http://www.gabotronics.com/download/resources/bmp-converter.zip) works very nicely for this.
Your new bitmap file will need to be converted to run-length encoding compressed hexidecimal. The [Gabotronics Image to HEX Converter v1.03](http://www.gabotronics.com/download/resources/bmp-converter.zip) works very nicely for this.
The proper settings are shown in the screenshot below:
@ -38,10 +38,10 @@ 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 https://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```.
Extract the contents of this archive to any folder of your choice, for instance ```C:\dev\gcc-arm-none-eabi-4_8-2014q2```.
![GNU ARM Toolchain Setup](assets/008.toolchain.png)
@ -51,9 +51,9 @@ add the "bin" subdirectory to the PATH Windows environment variable: ```%PATH%;C
![GNU ARM Toolchain Setup](assets/010.toolchain_path.png)
## Checkout and compile Cleanflight
## Checkout and compile INAV
Head over to the Cleanflight Github page and grab the URL of the GIT Repository: "https://github.com/cleanflight/cleanflight.git"
Head over to the INAV Github page and grab the URL of the GIT Repository: "https://github.com/cleanflight/cleanflight.git"
Open the Cygwin-Terminal, navigate to your development folder and use the git commandline to checkout the repository:
To compile your Cleanflight binaries, enter the cleanflight directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default NAZE target:
To compile your INAV binaries, enter the cleanflight directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default NAZE target:
Cleanflight provides Travis build and config files in the repository root.
INAV provides Travis build and config files in the repository root.
## Pushing builds to a remote server
@ -8,4 +8,4 @@ Cleanflight provides Travis build and config files in the repository root.
```PUBLISH_URL``` environment variable. If set, the build script will use the cURL binary and simulate
a file upload post to the configured server.
Pleas check the ```notifications``` section in the ```.travis.yml``` file and adjust the irc notifications if you plan on using Travis on your Cleanflight fork
Pleas check the ```notifications``` section in the ```.travis.yml``` file and adjust the irc notifications if you plan on using Travis on your INAV fork