diff --git a/README.md b/README.md index f620061d2..737b7517d 100644 --- a/README.md +++ b/README.md @@ -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) * Oneshot ESC support. * Blackbox flight recorder logging (to onboard flash or external SD card). @@ -50,11 +48,11 @@ http://www.multiwii.com/forum/viewtopic.php?f=23&t=5149 ## Installation -See: https://github.com/cleanflight/cleanflight/blob/master/docs/Installation.md +See: https://github.com/cleanflight/cleanflight/blob/master/docs/Installation.md ## Documentation -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. https://www.youtube.com/playlist?list=PL6H1fAj_XUNVBEcp8vbMH2DrllZAGWkt8 @@ -78,7 +76,7 @@ Please subscribe and '+1' the videos if you find them useful. ## Configuration Tool -To configure Cleanflight you should use the Cleanflight-configurator GUI tool (Windows/OSX/Linux) that can be found here: +To configure INAV you should use the INAV-configurator GUI tool (Windows/OSX/Linux) that can be found here: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb @@ -113,7 +111,5 @@ https://travis-ci.org/cleanflight/cleanflight [![Build Status](https://travis-ci.org/cleanflight/cleanflight.svg?branch=master)](https://travis-ci.org/cleanflight/cleanflight) -## Cleanflight Releases +## INAV Releases https://github.com/cleanflight/cleanflight/releases - - diff --git a/docs/1wire.md b/docs/1wire.md index 7d2473c36..979e17ba3 100644 --- a/docs/1wire.md +++ b/docs/1wire.md @@ -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. diff --git a/docs/API/MSP_extensions.md b/docs/API/MSP_extensions.md index a7ae4187a..357c6239e 100644 --- a/docs/API/MSP_extensions.md +++ b/docs/API/MSP_extensions.md @@ -1,7 +1,7 @@ # MSP Extensions -Cleanflight includes a number of extensions to the MultiWii Serial Protocol (MSP). This document describes -those extensions in order that 3rd party tools may identify cleanflight firmware and react appropriately. +INAV includes a number of extensions to the MultiWii Serial Protocol (MSP). This document describes +those extensions in order that 3rd party tools may identify INAV firmware and react appropriately. Issue the MSP_API_VERSION command to find out if the firmware supports them. @@ -28,7 +28,7 @@ Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | -Thus, for a cleanflight firmware with 40 slots 160 bytes would be returned in response to MSP\_MODE\_RANGES, +Thus, for a INAV firmware with 40 slots 160 bytes would be returned in response to MSP\_MODE\_RANGES, ### MSP\_SET\_MODE\_RANGE @@ -52,7 +52,7 @@ sending this message for all auxiliary slots. ### Implementation Notes -* The client should make no assumptions about the number of slots available. Rather, the number should be computed +* The client should make no assumptions about the number of slots available. Rather, the number should be computed from the size of the MSP\_MODE\_RANGES message divided by the size of the returned data element (4 bytes); * The client should ensure that all changed items are returned to the flight controller, including those where a switch or range has been disabled; @@ -86,7 +86,7 @@ Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the | adjustmentFunction | uint8 | See below | | auxSwitchChannelIndex | uint8 | The Aux channel number used to perform the function (indexed from 0) | -Thus, for a cleanflight firmware with 12 slots 72 bytes would be returned in response to MSP\_ADJUSTMENT\_RANGES, +Thus, for a INAV firmware with 12 slots 72 bytes would be returned in response to MSP\_ADJUSTMENT\_RANGES, ### MSP\_SET\_ADJUSTMENT\_RANGE @@ -128,7 +128,7 @@ note: it would be ideal to disable this when armed The FC maintains internal state for each adjustmentStateIndex, currently 4 simultaneous adjustment states are maintained. Multiple adjustment ranges can be configured to use the same state but care should be taken not to send multiple adjustment ranges that when active would confict. -e.g. Configuring two identical adjustment ranges using the same slot would conflict, but configuring two adjustment ranges that used +e.g. Configuring two identical adjustment ranges using the same slot would conflict, but configuring two adjustment ranges that used only one half of the possible channel range each but used the same adjustmentStateIndex would not conflict. The FC does NOT check for conflicts. @@ -139,7 +139,7 @@ There are many adjustments that can be made, the numbers of them and their use i ### Implementation Notes -* The client should make no assumptions about the number of slots available. Rather, the number should be computed +* The client should make no assumptions about the number of slots available. Rather, the number should be computed from the size of the MSP\_ADJUSTMENT\_RANGES message divided by the size of the returned data element (6 bytes); * The client should ensure that all changed items are returned to the flight controller, including those where a switch or range has been disabled; @@ -150,12 +150,12 @@ There are many adjustments that can be made, the numbers of them and their use i The following MSP commands are replaced by the MSP\_MODE\_RANGES and MSP\_SET\_MODE\_RANGE extensions, and are not recognised by -cleanflight. +INAV. * MSP\_BOX * MSP\_SET\_BOX See also -------- -Modes.md describes the user visible implementation for the cleanflight +Modes.md describes the user visible implementation for the INAV modes extension. diff --git a/docs/Battery.md b/docs/Battery.md index 000799442..f1762e714 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -1,6 +1,6 @@ # Battery Monitoring -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: | Setting | Description | -| ----------------------------- | -------------------------------------------------------- | +| ----------------------------- | -------------------------------------------------------- | | `current_meter_scale` | The throttle scaling factor [centiamps, i.e. 1/100th A] | | `current_meter_offset` | The current at zero throttle (while disarmed) [centiamps, i.e. 1/100th A] | @@ -134,19 +134,19 @@ current_meter_offset = Imin * 100 = 280 ``` #### Tuning Using Battery Charger Measurement If you cannot measure current draw directly, you can approximate it indirectly using your battery charger. -However, note it may be difficult to adjust `current_meter_offset` using this method unless you can +However, note it may be difficult to adjust `current_meter_offset` using this method unless you can measure the actual current draw with the craft disarmed. Note: + This method depends on the accuracy of your battery charger; results may vary. -+ If you add or replace equipment that changes the in-flight current draw (e.g. video transmitter, ++ If you add or replace equipment that changes the in-flight current draw (e.g. video transmitter, camera, gimbal, motors, prop pitch/sizes, ESCs, etc.), you should recalibrate. The general method is: 1. Fully charge your flight battery 2. Fly your craft, using >50% of your battery pack capacity (estimated) -3. Note Cleanflight's reported mAh draw +3. Note INAV's reported mAh draw 4. Re-charge your flight battery, noting the mAh charging data needed to restore the pack to fully charged 5. Adjust `current_meter_scale` to according to the formula given below 6. Repeat and test @@ -156,7 +156,7 @@ Given (a) the reported mAh draw and the (b) mAh charging data, calculate a new ` current_meter_scale = (charging_data_mAh / reported_draw_mAh) * old_current_meter_scale ``` For example, assuming: -+ A Cleanflight reported current draw of 1260 mAh ++ A INAV reported current draw of 1260 mAh + Charging data to restore full charge of 1158 mAh + A existing `current_meter_scale` value of 400 (the default) @@ -166,8 +166,3 @@ current_meter_scale = (charging_data_mAh / reported_draw_mAh) * old_current_mete = (1158 / 1260) * 400 = 368 ``` - - - - - diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 52157d39c..284973dcc 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -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 -[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en +[INAV Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en ## Configuring the Blackbox -The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control +The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which -decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs +decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs every iteration. If you're using a slower MicroSD card, you may need to reduce your logging rate to reduce the number of corrupted logged frames that `blackbox_decode` complains about. A rate of 1/2 is likely to work for most craft. -You can change the logging rate settings by entering the CLI tab in the [Cleanflight Configurator][] and using the `set` +You can change the logging rate settings by entering the CLI tab in the [INAV Configurator][] and using the `set` command, like so: ``` @@ -232,8 +232,8 @@ not diagnose flight problems like vibration or PID setting issues. The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm. -If your craft has a buzzer attached, you can use Cleanflight's arming beep to synchronize your Blackbox log with your -flight video. Cleanflight's arming beep is a "long, short" pattern. The beginning of the first long beep will be shown +If your craft has a buzzer attached, you can use INAV's arming beep to synchronize your Blackbox log with your +flight video. INAV's arming beep is a "long, short" pattern. The beginning of the first long beep will be shown as a blue line in the flight data log, which you can sync against your recorded audio track. You should wait a few seconds after disarming your craft to allow the Blackbox to finish saving its data. @@ -246,7 +246,7 @@ tools will ask you to pick which one of these flights you want to display/decode Don't insert or remove the SD card while the OpenLog is powered up. ### Usage - Dataflash chip -After your flights, you can use the [Cleanflight Configurator][] to download the contents of the dataflash to your +After your flights, you can use the [INAV Configurator][] to download the contents of the dataflash to your computer. Go to the "dataflash" tab and click the "save flash to file..." button. Saving the log can take 2 or 3 minutes. @@ -259,10 +259,10 @@ nothing will be recorded. ### Usage - Logging switch If you're recording to an onboard flash chip, you probably want to disable Blackbox recording when not required in order -to save storage space. To do this, you can add a Blackbox flight mode to one of your AUX channels on the Configurator's +to save storage space. To do this, you can add a Blackbox flight mode to one of your AUX channels on the Configurator's modes tab. Once you've added a mode, Blackbox will only log flight data when the mode is active. -A log header will always be recorded at arming time, even if logging is paused. You can freely pause and resume logging +A log header will always be recorded at arming time, even if logging is paused. You can freely pause and resume logging while in flight. ## Viewing recorded logs diff --git a/docs/Board - AlienWii32.md b/docs/Board - AlienWii32.md index 8697fe47f..79a0ed491 100644 --- a/docs/Board - AlienWii32.md +++ b/docs/Board - AlienWii32.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. \ No newline at end of file +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. diff --git a/docs/Board - CC3D.md b/docs/Board - CC3D.md index b42a14a7f..d96abce5e 100644 --- a/docs/Board - CC3D.md +++ b/docs/Board - CC3D.md @@ -12,7 +12,7 @@ have an on-board USB to uart adapter which connect to the processor's serial por The board cannot currently be used for hexacopters/octocopters. -Tricopter & Airplane support is untested, please report success or failure if you try it. +Tricopter & Airplane support is untested, please report success or failure if you try it. # Pinouts @@ -30,6 +30,7 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SE | 8 | PPM Input | Enable `feature RX_PPM` | *Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input. + NOTE: for the CC3D\_PPM1 build PPM input is on Pin 3 and RSSI\_ADC is on Pin 8 The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode @@ -49,7 +50,7 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_ | --- | ---------| ------| | 1 | Ground | | | 2 | +5V | | -| 3 | Unused | | +| 3 | Unused | | | 4 | CH1 | | | 5 | CH2 | | | 6 | CH3 | | @@ -106,10 +107,10 @@ You cannot use USART3 and I2C at the same time. # Flashing -There are two primary ways to get Cleanflight onto a CC3D board. +There are two primary ways to get INAV onto a CC3D board. * Single binary image mode - best mode if you don't want to use OpenPilot. -* OpenPilot Bootloader compatible image mode - best mode if you want to switch between OpenPilot and Cleanflight. +* OpenPilot Bootloader compatible image mode - best mode if you want to switch between OpenPilot and INAV. ## Single binary image mode. @@ -144,14 +145,14 @@ If you have a JLink debugger, you can use JLinkExe to flash the open pilot bootl Here's an example session: ``` -$ /Applications/SEGGER/JLink/JLinkExe +$ /Applications/SEGGER/JLink/JLinkExe SEGGER J-Link Commander V4.90c ('?' for help) Compiled Aug 29 2014 09:52:38 DLL version V4.90c, compiled Aug 29 2014 09:52:33 Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04 Hardware: V7.00 -S/N: -1 -Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull +S/N: -1 +Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull VTarget = 3.300V Info: Could not measure total IR len. TDO is constant high. Info: Could not measure total IR len. TDO is constant high. @@ -189,5 +190,5 @@ Info: J-Link: Flash download: Flash download into internal flash skipped. Flash Info: J-Link: Flash download: Total time needed: 0.898s (Prepare: 0.709s, Compare: 0.128s, Erase: 0.000s, Program: 0.000s, Verify: 0.000s, Restore: 0.059s) O.K. J-Link>q -$ +$ ``` diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index a37720610..09f14b4f6 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -1,6 +1,6 @@ # Board - CJMCU -The CJMCU is a tiny (80mm) board running a STM32F103, which contains a 3-Axis Compass (HMC5883L) +The CJMCU is a tiny (80mm) board running a STM32F103, which contains a 3-Axis Compass (HMC5883L) and an Accelerometer/Gyro (MPU6050). This board does not have an onboard USB-Serial converter, so an external adapter is needed. @@ -60,7 +60,7 @@ USART2 is the following pins. In standard QUADX configuration, the motors are mapped: -| Cleanflight | CJMCU | +| INAV | CJMCU | | ----------- | ------ | | Motor 1 | Motor3 | | Motor 2 | Motor2 | @@ -89,19 +89,19 @@ You will need a USB -> Serial UART adapter. Connect: | RX | TX | | TX | RX | -When first connected this should power up the board, and will be in bootloader mode. If this does not happen, check +When first connected this should power up the board, and will be in bootloader mode. If this does not happen, check the charge switch is set to POW. -After the flashing process has been completed, this will allow access via the cleanflight configurator to change +After the flashing process has been completed, this will allow access via the INAV configurator to change settings or flash a new firmware. -WARNING: If the motors are connected and the board boots into the bootloader, they will start +WARNING: If the motors are connected and the board boots into the bootloader, they will start to spin after around 20 seconds, it is recommended not to connect the motors until the board is flashed. # Flashing To flash the board: - * Open Cleanflight Configurator + * Open INAV Configurator * Choose the latest CJMCU firmware from the list. * Select "Load Firmware [Online]" and wait for the firmware to download. * Tick "No Reboot Sequence" and "Full Chip Erase" @@ -138,8 +138,7 @@ The two nearby LEDs will show the status of charging: # Helpful Hints - * If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500 + * If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500 for one of the the AUX channels which will result in it being always on * Enabling the feature MOTOR_STOP helps with crashes so it doesn't try to keep spinning on its back * When the power runs low, the quad will start jumping around a bit, if the flight behaviour seems strange, check your batteries charge - diff --git a/docs/Board - MotoLab.md b/docs/Board - MotoLab.md index 6052d576b..8a5f0f90f 100644 --- a/docs/Board - MotoLab.md +++ b/docs/Board - MotoLab.md @@ -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: ``` dd if=/dev/zero of=zero.bin bs=1 count=262144 ``` @@ -99,4 +99,3 @@ dd if=/dev/zero of=zero.bin bs=1 count=262144 ## Todo Pinout documentation - diff --git a/docs/Board - Naze32.md b/docs/Board - Naze32.md index 04d37f006..5ea0825ca 100644 --- a/docs/Board - Naze32.md +++ b/docs/Board - Naze32.md @@ -13,7 +13,7 @@ if found please report via the [github issue tracker](https://github.com/cleanfl | 4 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | | | 5 | SOFTSERIAL2 | RC7 / PB0 | RC8 / PB1 | | -* You cannot use USART1/TX/TELEM pins at the same time. +* You cannot use USART1/TX/TELEM pins at the same time. * You may encounter flashing problems if you have something connected to the RX/TX pins. Try disconnecting RX/TX. ## Pinouts @@ -24,10 +24,10 @@ The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SER | --- | ---------- | --------------------------- | -------------------------------- | | 1 | | Ground | | | 2 | Circle | +5V | | -| 3 | 1 | RX_PPM | Enable `feature RX_PPM` | -| 4 | 2 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input | -| 5 | 3 | USART2 TX | | -| 6 | 4 | USART2 RX | | +| 3 | 1 | RX_PPM | Enable `feature RX_PPM` | +| 4 | 2 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input | +| 5 | 3 | USART2 TX | | +| 6 | 4 | USART2 RX | | | 7 | 5 | LED_STRIP | Enable `feature LED_STRIP` | | 8 | 6 | unused | | | 9 | 7 | Sonar Trigger | | @@ -49,9 +49,9 @@ When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two + Apply power to the board + Remove the short on the board -### Cleanflight configurator -+ Select the correct hardware and the desired release of the Clearflight firmware -+ Put a check in the "No reboot sequence" +### INAV configurator ++ Select the correct hardware and the desired release of the INAV firmware ++ Put a check in the "No reboot sequence" + Flash firmware ``` @@ -66,4 +66,3 @@ When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two |O O| \-------[USB]-------/ ``` - diff --git a/docs/Board - SPRacingF3.md b/docs/Board - SPRacingF3.md index 192cc2a74..bffd7b70a 100644 --- a/docs/Board - SPRacingF3.md +++ b/docs/Board - SPRacingF3.md @@ -1,6 +1,6 @@ # Board - SPRacingF3 -The Seriously Pro Racing MOF3 board (SPRacingF3) is the first board designed specifically for Cleanflight. +The Seriously Pro Racing MOF3 board (SPRacingF3) is the first board designed specifically for INAV. Full details available on the website, here: @@ -18,7 +18,7 @@ http://seriouslypro.com/spracingf3 * Dedicated I2C port for connection of OLED display without needing flight battery. * Battery monitoring ports for voltage and current. * Buzzer port for audible warnings and notifications. -* Solder pads in addition to connectors for Sonar, PPM, RSSI, Current, GPIO, LED Strip, 3.3v, +* Solder pads in addition to connectors for Sonar, PPM, RSSI, Current, GPIO, LED Strip, 3.3v, * Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader. * Symmetrical design for a super tidy wiring. * Wire up using using pin headers, JST-SH sockets or solder pads. Use either right-angled or straight pin-headers. @@ -63,9 +63,9 @@ When RX_PPM/RX_SERIAL is used the IO_1 pinout is as follows. | 1 | Ground | | | 2 | VCC_IN | Voltage as-supplied by BEC. | | 3 | RX_PPM | Enable `feature RX_PPM` | -| 4 | GPIO | | -| 5 | SoftSerial1_RX | | -| 6 | SoftSerial1_TX | | +| 4 | GPIO | | +| 5 | SoftSerial1_RX | | +| 6 | SoftSerial1_TX | | | 7 | LED_STRIP | Enable `feature LED_STRIP` | | 8 | VCC | 3.3v output for LOW CURRENT application only | @@ -91,9 +91,9 @@ When RX_PPM/RX_SERIAL is used the IO_2 pinout is as follows. | 1 | Ground | | | 2 | VCC_IN | Voltage as-supplied by BEC. | | 3 | RX_SERIAL | UART3 RX | -| 4 | | UART3_TX | -| 5 | SONAR_TRIG/SoftSerial2_RX | Enable `feature SONAR/SOFTSERIAL` | -| 6 | SONAR_ECHO/SoftSerial2_TX | Enable `feature SONAR/SOFTSERIAL` | +| 4 | | UART3_TX | +| 5 | SONAR_TRIG/SoftSerial2_RX | Enable `feature SONAR/SOFTSERIAL` | +| 6 | SONAR_ECHO/SoftSerial2_TX | Enable `feature SONAR/SOFTSERIAL` | | 7 | ADC_1 | Current Sensor | | 8 | ADC_2 | RSSI | @@ -125,4 +125,3 @@ The port cannot be used at the same time as UART2. | 2 | NRST | Voltage as-supplied by BEC OR USB, always on | | 3 | SWDIO | | | 4 | SWDCLK | | - diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index 12ee02352..23ddcbf46 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -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: `Battery (+) ---< R1 >--- PWM9 ---< R2 >--- Battery (-)` - + * R1 = 8k2 (Grey Red Red) * R2 = 2k0 (Red Black Red) - + This gives a 2.2k for an 11.2v battery. The `vbat_scale` for this divider should be set around `52`. ## Current Monitoring -Connect a current sensor to PWM8/PA7 that gives a range between 0v and 3.3v out (MAX). \ No newline at end of file +Connect a current sensor to PWM8/PA7 that gives a range between 0v and 3.3v out (MAX). diff --git a/docs/Boards.md b/docs/Boards.md index 4afb25ee9..2cc325b05 100644 --- a/docs/Boards.md +++ b/docs/Boards.md @@ -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. diff --git a/docs/Buzzer.md b/docs/Buzzer.md index 7f219646f..de682e7f2 100644 --- a/docs/Buzzer.md +++ b/docs/Buzzer.md @@ -1,6 +1,6 @@ # Buzzer -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 : +Sequences: 0 GYRO_CALIBRATED 20, 10, 20, 10, 20, 10 Gyro is calibrated 1 RX_LOST_LANDING 10, 10, 10, 10, 10, 40, 40, 10, 40, 10, 40, 40, 10, 10, 10, 10, 10, 70 SOS morse code @@ -33,7 +33,7 @@ Sequences available in Cleanflight v1.9 and above are : 4 ARMING 30, 5, 5, 5 Arming the board 5 ARMING_GPS_FIX 5, 5, 15, 5, 5, 5, 15, 30 Arming and GPS has fix 6 BAT_CRIT_LOW 50, 2 Battery is critically low (repeats) - 7 BAT_LOW 25, 50 Battery is getting low (repeats) + 7 BAT_LOW 25, 50 Battery is getting low (repeats) 8 NULL multi beeps GPS status (sat count) 9 RX_SET 10, 10 RX is set (when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled) 10 ACC_CALIBRATION 5, 5, 5, 5 ACC inflight calibration completed diff --git a/docs/Cli.md b/docs/Cli.md index 064812382..6c9be5ea4 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -1,6 +1,6 @@ # Command Line Interface (CLI) -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 | | `blackbox_rate_num` | | 1 | 32 | 1 | Master | UINT8 | | `blackbox_rate_denom` | | 1 | 32 | 1 | Master | UINT8 | -| `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. | 10 | 255 | 40 | Profile | UINT8 | diff --git a/docs/Configuration.md b/docs/Configuration.md index 9e187766c..c6ab372ec 100644 --- a/docs/Configuration.md +++ b/docs/Configuration.md @@ -1,6 +1,6 @@ # Configuration -Cleanflight is configured primarily using the Cleanflight Configurator GUI. +INAV is configured primarily using the INAV 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,21 +15,21 @@ __Due to ongoing development, the fact that the GUI cannot yet backup all your s ## GUI -![Cleanflight Gui](Screenshots/cleanflight-gui.png) +![INAV Gui](Screenshots/cleanflight-gui.png) 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. diff --git a/docs/Display.md b/docs/Display.md index c0413b45d..2215f6363 100755 --- a/docs/Display.md +++ b/docs/Display.md @@ -1,6 +1,6 @@ # Display -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 * [wide.hk](http://www.wide.hk/products.php?product=I2C-0.96%22-OLED-display-module-%28-compatible-Arduino-%29) I2C 0.96" OLED display module * [witespyquad.gostorego.com](http://witespyquad.gostorego.com/accessories/readytofly-1-oled-128x64-pid-tuning-display-i2c.html) ReadyToFlyQuads 1" OLED Display @@ -68,5 +68,3 @@ More can be read about this procedure here: http://www.multiwii.com/forum/viewto Connect +5v, Ground, I2C SDA and I2C SCL from the flight controller to the display. On Naze32 rev 5 boards the SDA and SCL pads are underneath the board. - - diff --git a/docs/Getting Started.md b/docs/Getting Started.md index b0836255f..91be09480 100644 --- a/docs/Getting Started.md +++ b/docs/Getting Started.md @@ -1,20 +1,20 @@ # Getting Started -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) diff --git a/docs/Gps.md b/docs/Gps.md index f5c4bc8ea..387810626 100644 --- a/docs/Gps.md +++ b/docs/Gps.md @@ -1,6 +1,6 @@ # GPS -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. +Below are some examples of user-tested hardware. ### Ublox diff --git a/docs/Gtune.md b/docs/Gtune.md index c7e4a6714..266b44cd5 100644 --- a/docs/Gtune.md +++ b/docs/Gtune.md @@ -6,7 +6,7 @@ The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gm > http://diydrones.com/profiles/blogs/zero-pid-tunes-for-multirotors-part-2 > http://www.multiwii.com/forum/viewtopic.php?f=8&t=5190 -The G-Tune functionality for Cleanflight is ported from the Harakiri firmware. +The G-Tune functionality for INAV is ported from the Harakiri firmware. ## Safety preamble: _Use at your own risk_ diff --git a/docs/Inflight Adjustments.md b/docs/Inflight Adjustments.md index c6889a48a..f0bbf6bea 100644 --- a/docs/Inflight Adjustments.md +++ b/docs/Inflight Adjustments.md @@ -1,6 +1,6 @@ # In-flight Adjustments -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. diff --git a/docs/Installation.md b/docs/Installation.md index 5c3913eb3..38e9470fd 100644 --- a/docs/Installation.md +++ b/docs/Installation.md @@ -3,16 +3,16 @@ ## Using the configurator 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! diff --git a/docs/Introduction.md b/docs/Introduction.md index 71d4f3983..665ccd922 100644 --- a/docs/Introduction.md +++ b/docs/Introduction.md @@ -1,10 +1,10 @@ -# Cleanflight +# INAV -![Cleanflight](assets/cleanflight/cleanflight-logo-light-wide-1-240px.jpg) +![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png) Welcome to CleanFlight! -Cleanflight is an community project which attempts to deliver flight controller firmware and related tools. +INAV is an community project which attempts to deliver flight controller firmware and related tools. ## Primary Goals diff --git a/docs/LedStrip.md b/docs/LedStrip.md index 89eb759e6..57805fa5a 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -1,6 +1,6 @@ # LED Strip -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 - + ### Exmple 28 LED config ``` @@ -463,7 +463,7 @@ led 27 2,9:S:FWT:0 ``` 16-18 9-11 19-21 \ / 6-8 - \ 12-15 / + \ 12-15 / \ FRONT / / BACK \ / \ diff --git a/docs/Migrating from baseflight.md b/docs/Migrating from baseflight.md deleted file mode 100644 index 58e6f0513..000000000 --- a/docs/Migrating from baseflight.md +++ /dev/null @@ -1,103 +0,0 @@ -# Migrating from baseflight - -## Procedure - -**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 diff --git a/docs/Mixer.md b/docs/Mixer.md index 3c2dd9b23..4ebf14ef9 100644 --- a/docs/Mixer.md +++ b/docs/Mixer.md @@ -1,6 +1,6 @@ # Mixer -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 |----|--------------| | 0 | GIMBAL PITCH | | 1 | GIMBAL ROLL | -| 2 | ELEVATOR / SINGLECOPTER_4 | +| 2 | ELEVATOR / SINGLECOPTER_4 | | 3 | FLAPPERON 1 (LEFT) / SINGLECOPTER_1 | | 4 | FLAPPERON 2 (RIGHT) / BICOPTER_LEFT / DUALCOPTER_LEFT / SINGLECOPTER_2 | | 5 | RUDDER / BICOPTER_RIGHT / DUALCOPTER_RIGHT / SINGLECOPTER_3 | -| 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. | Pins | Outputs | |------|------------------| diff --git a/docs/Modes.md b/docs/Modes.md index 3e8e78d73..d272b54c3 100644 --- a/docs/Modes.md +++ b/docs/Modes.md @@ -1,6 +1,6 @@ # Modes -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. - diff --git a/docs/Navigation.md b/docs/Navigation.md index ac8fa7efa..9d33f1064 100755 --- a/docs/Navigation.md +++ b/docs/Navigation.md @@ -1,6 +1,6 @@ # Navigation -Navigation system in Cleanflight is responsible for assisting the pilot allowing altitude and position hold, return-to-home and waypoint flight. +Navigation system in INAV is responsible for assisting the pilot allowing altitude and position hold, return-to-home and waypoint flight. ## NAV ALTHOLD mode - altitude hold diff --git a/docs/PID tuning.md b/docs/PID tuning.md index 35d19a9b1..932fd4277 100644 --- a/docs/PID tuning.md +++ b/docs/PID tuning.md @@ -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 diff --git a/docs/Profiles.md b/docs/Profiles.md index a8fb592e2..06d4546a1 100644 --- a/docs/Profiles.md +++ b/docs/Profiles.md @@ -22,7 +22,7 @@ profile # Rate Profiles -Cleanflight supports rate profiles in addition to regular profiles. +INAV supports rate profiles in addition to regular profiles. Rate profiles contain settings that adjust how your craft behaves based on control input. @@ -31,7 +31,7 @@ Three rate profiles are supported. Rate profiles can be selected while flying using the inflight adjustments feature. Each normal profile has a setting called 'default_rate_profile`. When a profile is activated the -corresponding rate profile is also activated. +corresponding rate profile is also activated. Profile 0 has a default rate profile of 0. Profile 1 has a default rate profile of 1. diff --git a/docs/Rx.md b/docs/Rx.md index 5be46cfbb..40d6bc7cb 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -68,7 +68,7 @@ http://www.futaba-rc.com/systems/futk8100-8j/ #### OpenTX S.BUS configuration If using OpenTX set the transmitter module to D16 mode and ALSO select CH1-16 on the transmitter before binding to allow reception -of all 16 channels. +of all 16 channels. OpenTX 2.09, which is shipped on some Taranis X9D Plus transmitters, has a bug - [issue:1701](https://github.com/opentx/opentx/issues/1701). The bug prevents use of all 16 channels. Upgrade to the latest OpenTX version to allow correct reception of all 16 channels, @@ -124,7 +124,7 @@ firmware on the tx to make use of these extra channels. ## MultiWii serial protocol (MSP) Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP. - + ## Configuration There are 3 features that control receiver mode: @@ -160,9 +160,9 @@ A flight channel can either be AUTOMATIC or HOLD, an AUX channel can either be S * AUTOMATIC - Flight channels are set to safe values (low throttle, mid position for yaw/pitch/roll). * HOLD - Channel holds the last value. -* SET - Channel is set to a specific configured value. +* SET - Channel is set to a specific configured value. -The default mode is AUTOMATIC for flight channels and HOLD for AUX channels. +The default mode is AUTOMATIC for flight channels and HOLD for AUX channels. The rxfail command can be used in conjunction with mode ranges to trigger various actions. @@ -197,11 +197,11 @@ WARNING: Always make sure you test the behavior is as expected after configuring #### `rx_min_usec` -The lowest channel value considered valid. e.g. PWM/PPM pulse length +The lowest channel value considered valid. e.g. PWM/PPM pulse length #### `rx_max_usec` -The highest channel value considered valid. e.g. PWM/PPM pulse length +The highest channel value considered valid. e.g. PWM/PPM pulse length ### Serial RX @@ -248,13 +248,13 @@ Set failsafe on the throttle channel in the receiver settings (via transmitter m This is the prefered way, since this is *much faster* detected by the FC then a channel that sends no pulses (OFF). __NOTE:__ -One or more control channels may be set to OFF to signal a failsafe condition to the FC, all other channels *must* be set to either HOLD or OFF. +One or more control channels may be set to OFF to signal a failsafe condition to the FC, all other channels *must* be set to either HOLD or OFF. Do __NOT USE__ the mode indicated with FAILSAFE instead, as this combination is NOT handled correctly by the FC. ## Receiver Channel Range Configuration. If you have a transmitter/receiver, that output a non-standard pulse range (i.e. 1070-1930 as some Spektrum receivers) -you could use rx channel range configuration to map actual range of your transmitter to 1000-2000 as expected by Cleanflight. +you could use rx channel range configuration to map actual range of your transmitter to 1000-2000 as expected by INAV. The low and high value of a channel range are often referred to as 'End-points'. e.g. 'End-point adjustments / EPA'. @@ -272,7 +272,7 @@ save ``` Now reboot your FC, connect the configurator, go to the `Receiver` tab move sticks on your transmitter and note min and -max values of first 4 channels. Take caution as you can accidentally arm your craft. Best way is to move one channel at +max values of first 4 channels. Take caution as you can accidentally arm your craft. Best way is to move one channel at a time. Go to CLI and set the min and max values with the following command: diff --git a/docs/Serial.md b/docs/Serial.md index 0061dd172..3cf13bdc7 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -1,8 +1,8 @@ # Serial -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: | 5 | 115200 | | 6 | 230400 | | 7 | 250000 | - diff --git a/docs/Telemetry.md b/docs/Telemetry.md index dc58dfb82..6825d021c 100644 --- a/docs/Telemetry.md +++ b/docs/Telemetry.md @@ -35,7 +35,7 @@ set telemetry_inversion = 1 ### Precision setting for VFAS -Cleanflight can send VFAS (FrSky Ampere Sensor Voltage) in two ways: +INAV can send VFAS (FrSky Ampere Sensor Voltage) in two ways: ``` set frsky_vfas_precision = 0 @@ -89,13 +89,13 @@ Note: The SoftSerial ports may not be 5V tolerant on your board. Verify if you LTM is a lightweight streaming telemetry protocol supported by a number of OSDs, ground stations and antenna trackers. -The Cleanflight implementation of LTM implements the following frames: +The INAV implementation of LTM implements the following frames: * G-FRAME: GPS information (lat, long, ground speed, altitude, sat info) * A-FRAME: Attitude (pitch, roll, heading) * S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item - suffixed '+' not implemented in Cleanflight. + suffixed '+' not implemented in INAV. * O-FRAME: Origin (home position, lat, long, altitude, fix) In addition, in the inav (navigation-rewrite) fork: @@ -103,7 +103,7 @@ In addition, in the inav (navigation-rewrite) fork: Waypoint number, Nav Error, Nav Flags). LTM is transmit only, and can work at any supported baud rate. It is -designed to operate over 2400 baud (9600 in Cleanflight) and does not +designed to operate over 2400 baud (9600 in INAV) and does not benefit from higher rates. It is thus usable on soft serial. More information about the fields, encoding and enumerations may be diff --git a/docs/development/Bitmap Creation.md b/docs/development/Bitmap Creation.md index 398fa8fc4..ccc9d2b7a 100644 --- a/docs/development/Bitmap Creation.md +++ b/docs/development/Bitmap Creation.md @@ -1,6 +1,6 @@ # Bitmaps -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: -![Photoshop](assets/gabotronics.jpg) \ No newline at end of file +![Photoshop](assets/gabotronics.jpg) diff --git a/docs/development/Blackbox Internals.md b/docs/development/Blackbox Internals.md index f2b6b88fd..408ee2012 100644 --- a/docs/development/Blackbox Internals.md +++ b/docs/development/Blackbox Internals.md @@ -2,7 +2,7 @@ The Blackbox is designed to record the raw internal state of the flight controller at near-maximum rate. By logging the raw inputs and outputs of key flight systems, the Blackbox log aims to allow the offline bench-top simulation, debugging, -and testing of flight control algorithms using data collected from real flights. +and testing of flight control algorithms using data collected from real flights. A typical logging regime might capture 30 different state variables (for an average of 28 bytes per frame) at a sample rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with a typical 8-N-1 serial encoding. @@ -11,7 +11,7 @@ rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with Please refer to the source code to clarify anything this document leaves unclear: -* Cleanflight's Blackbox logger: [blackbox.c](https://github.com/cleanflight/cleanflight/blob/master/src/main/blackbox/blackbox.c), +* INAV's Blackbox logger: [blackbox.c](https://github.com/cleanflight/cleanflight/blob/master/src/main/blackbox/blackbox.c), [blackbox_io.c](https://github.com/cleanflight/cleanflight/blob/master/src/main/blackbox/blackbox_io.c), [blackbox_fielddefs.h](https://github.com/cleanflight/cleanflight/blob/master/src/main/blackbox/blackbox_fielddefs.h) * [C implementation of the Blackbox log decoder](https://github.com/cleanflight/blackbox-tools/blob/master/src/parser.c) @@ -36,7 +36,7 @@ iteration. Each main frame must contain at least two fields, "loopIteration" which records the index of the current main loop iteration (starting at zero for the first logged iteration), and "time" which records the timestamp of the beginning of -the main loop in microseconds (this needn't start at zero, on Cleanflight it represents the system uptime). +the main loop in microseconds (this needn't start at zero, on INAV it represents the system uptime). There are two kinds of main frames, "I" and "P". "I", or "intra" frames are like video keyframes. They can be decoded without reference to any previous frame, so they allow log decoding to be resynchronized in the event of log damage. "P" @@ -50,7 +50,7 @@ intra/inter encoding system. The "H" or "home" frame records the lat/lon of a reference point. The "G" or "GPS" frame records the current state of the GPS system (current position, altitude etc.) based on the reference point. The reference point can be updated -(infrequently) during the flight, and is logged whenever it changes. +(infrequently) during the flight, and is logged whenever it changes. To allow "G" frames to continue be decoded in the event that an "H" update is dropped from the log, the "H" frame is logged periodically even if it has not changed (say, every 10 seconds). This caps the duration of unreadble "G" frames @@ -65,7 +65,7 @@ All Slow frames are logged as intraframes. An interframe encoding scheme can't b damaged frame causes all subsequent interframes to be undecodable. Because Slow frames are written so infrequently, one missing Slow frame could invalidate minutes worth of Slow state. -On Cleanflight, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe +On INAV, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe state. ### Event frames: E @@ -74,9 +74,9 @@ controller "state". Instead, we log it as a state *transition* . This data is lo frame payload begins with a single byte "event type" field. The format of the rest of the payload is not encoded in the flight log, so its interpretation is left up to an agreement of the writer and the decoder. -For example, one event that Cleanflight logs is that the user has adjusted a system setting (such as a PID setting) -using Cleanflight's inflight adjustments feature. The event payload notes which setting was adjusted and the new value -for the setting. +For example, one event that INAV logs is that the user has adjusted a system setting (such as a PID setting) +using INAV's inflight adjustments feature. The event payload notes which setting was adjusted and the new value +for the setting. Because these setting updates are so rare, it would be wasteful to treat the settings as "state" and log the fact that the setting had not been changed during every logging iteration. It would be infeasible to periodically log the system @@ -94,7 +94,7 @@ the raw field value. Finally, the encoder is used to transform the value into by ### Field predictors The job of the predictor is to bring the value to be encoded as close to zero as possible. The predictor may be based on the values seen for the field in a previous frame, or some other value such as a fixed value or a value recorded in -the log headers. For example, the battery voltage values in "I" intraframes in Cleanflight use a reference voltage that +the log headers. For example, the battery voltage values in "I" intraframes in INAV use a reference voltage that is logged as part of the headers as a predictor. This assumes that battery voltages will be broadly similar to the initial pack voltage of the flight (e.g. 4S battery voltages are likely to lie within a small range for the whole flight). In "P" interframes, the battery voltage will instead use the previously-logged voltage as a predictor, because @@ -125,7 +125,7 @@ history is a better predictor of the next value than the previous value on its o or motor measurements). #### Predict minthrottle (4) -This predictor subtracts the value of "minthrottle" which is included in the log header. In Cleanflight, motors always +This predictor subtracts the value of "minthrottle" which is included in the log header. In INAV, motors always lie in the range of `[minthrottle ... maxthrottle]` when the craft is armed, so this predictor is used for the first motor value in intraframes. @@ -142,12 +142,12 @@ This predictor is set to the corresponding latitude or longitude field from the a preceding "H" frame). If no preceding "H" frame exists, the value is marked as invalid. #### Predict 1500 (8) -This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these +This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these typically lie close to the midpoint of 1500us. #### Predict vbatref (9) This predictor is set to the "vbatref" field written in the log header. It is used when logging intraframe battery -voltages in Cleanflight, since these are expected to be broadly similar to the first battery voltage seen during +voltages in INAV, since these are expected to be broadly similar to the first battery voltage seen during arming. #### Predict last main-frame time (10) @@ -192,7 +192,7 @@ Here are some example values encoded using variable-byte encoding: | 128 | 0x80 0x01 | | 129 | 0x81 0x01 | | 23456 | 0xA0 0xB7 0x01 | - + #### Signed variable byte (0) This encoding applies a pre-processing step to fold negative values into positive ones, then the resulting unsigned number is encoded using unsigned variable byte encoding. The folding is accomplished by "ZigZag" encoding, which is @@ -219,7 +219,7 @@ Here are some example integers encoded using ZigZag encoding: #### Neg 14-bit (3) The value is negated, treated as an unsigned 14 bit integer, then encoded using unsigned variable byte encoding. This -bizarre encoding is used in Cleanflight for battery pack voltages. This is because battery voltages are measured using a +bizarre encoding is used in INAV for battery pack voltages. This is because battery voltages are measured using a 14-bit ADC, with a predictor which is set to the battery voltage during arming, which is expected to be higher than any voltage experienced during flight. After the predictor is subtracted, the battery voltage will almost certainly be below zero. @@ -233,7 +233,7 @@ number of bytes. If the bitstream isn't aligned on a byte boundary by the time t or the end of the frame is reached, the final byte is padded with zeros byte-align the stream. This encoding requires more CPU time than the other encodings because of the bit juggling involved in writing the bitstream. -When this encoder is chosen to encode all of the values in Cleanflight interframes, it saves about 10% bandwidth +When this encoder is chosen to encode all of the values in INAV interframes, it saves about 10% bandwidth compared to using a mixture of the other encodings, but uses too much CPU time to be practical. [The basic encoding algorithm is defined on Wikipedia](https://en.wikipedia.org/wiki/Elias_delta_coding). Given these @@ -242,13 +242,13 @@ utility functions: ```c /* Write `bitCount` bits from the least-significant end of the `bits` integer to the bitstream. The most-significant bit * will be written first - */ + */ void writeBits(uint32_t bits, unsigned int bitCount); /* Returns the number of bits needed to hold the top-most 1-bit of the integer 'i'. 'i' must not be zero. */ unsigned int numBitsToStoreInteger(uint32_t i); ``` - + This is our reference implementation of Elias Delta: ```c @@ -262,10 +262,10 @@ void writeU32EliasDeltaInternal(uint32_t value) // Use unary to encode the number of bits we'll need to write the length of the value writeBits(0, lengthOfValueLen - 1); - + // Now write the length of the value writeBits(valueLen, lengthOfValueLen); - + // Having now encoded the position of the top bit of value, write its remaining bits writeBits(value, valueLen - 1); } @@ -278,7 +278,7 @@ void writeU32EliasDelta(uint32_t value) { /* We can't encode value==0, so we need to add 1 to the value before encoding * - * That would make it impossible to encode MAXINT, so use 0xFFFFFFFF as an escape + * That would make it impossible to encode MAXINT, so use 0xFFFFFFFF as an escape * code with an additional bit to choose between MAXINT-1 or MAXINT. */ if (value >= 0xFFFFFFFE) { @@ -346,7 +346,7 @@ This would be encoded: ``` 0b00010100, 0x04, 0x08 -``` +``` #### TAG2_3S32 (7) A 2-bit header is written, followed by 3 signed field values of up to 32 bits each. The header value is based on the @@ -400,7 +400,7 @@ number of bits required to encode that field as follows: | 2 | 8 bits | [-128...127] | | 3 | 16 bits | [-32768...32767] | -This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the +This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the most-significant bit of the first field ending up in the most-significant bits of the first written byte. If the number of nibbles written is odd, the final byte has its least-significant nibble set to zero. @@ -440,7 +440,7 @@ log payload data, and finally an optional "log end" event ("E" frame). A single log file can be comprised of one or more logging sessions. Each session may be preceded and followed by any amount of non-Blackbox data. This data is ignored by the Blackbox log decoding tools. This allows for the logging device -to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a +to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a separate log file for each separate activity. ### Log start marker @@ -449,14 +449,14 @@ used to discover the beginning of the flight log if the log begins partway throu string, it is not expected to occur by accident in any sequence of random bytes from other log device users. ### Log header -The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value` +The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value` and ends with a '\n'. The overall header does not have a terminator to separate it from the log payload (the header implicitly ends when a line does not begin with an 'H' character). The header can contain some of these fields: #### Data version (required) -When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is +When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is incremented to allow backwards-compatibility in the decoder: ``` @@ -502,7 +502,7 @@ if (iteration % I_INTERVAL == 0) if ((iteration % I_INTERVAL + num - 1) % denom < num) return 'P'; - + return '.'; // i.e. don't log this iteration ``` @@ -524,7 +524,7 @@ Because Blackbox records the internal flight controller state, the interpretatio on knowing which flight controller recorded it. To accomodate this, the name of the flight controller should be recorded: ``` -H Firmware type:Cleanflight +H Firmware type:INAV ``` More details should be included to help narrow down the precise flight-controller version (but these are not required): @@ -570,11 +570,11 @@ H Field X encoding:1,1,0,0... This header provides the reference voltage that will be used by predictor #9. #### minthrottle -This header provides the minimum value sent by Cleanflight to the ESCs when armed, it is used by predictor #4. +This header provides the minimum value sent by INAV to the ESCs when armed, it is used by predictor #4. #### Additional headers The decoder ignores headers that it does not understand, so you can freely add any headers that you require in order to -properly interpret the meaning of the logged values. +properly interpret the meaning of the logged values. For example, to create a graphical displays of RC sticks and motor percentages, the Blackbox rendering tool requires the additional headers "rcRate" and "maxthrottle". In order to convert raw gyroscope, accelerometer and voltage readings @@ -671,4 +671,4 @@ immediately after the frame-start byte of the frame that was rejected. A rejecte interframes to be rejected as well, up until the next intraframe. A frame is also rejected if the "loopIteration" or "time" fields have made unreasonable leaps forward, or moved at -all backwards. This suffices to detect almost all log corruption. \ No newline at end of file +all backwards. This suffices to detect almost all log corruption. diff --git a/docs/development/Building in Mac OS X.md b/docs/development/Building in Mac OS X.md index ddad2e706..70f62e65a 100755 --- a/docs/development/Building in Mac OS X.md +++ b/docs/development/Building in Mac OS X.md @@ -4,7 +4,7 @@ Building in Mac OS X can be accomplished in just a few steps: * Install general development tools (clang, make, git) * Install ARM GCC 4.9 series compiler -* Checkout Cleanflight sourcecode through git +* Checkout INAV sourcecode through git * Build the code ## Install general development tools (clang, make, git) @@ -30,18 +30,18 @@ If you just get an error like this instead of a helpful popup prompt: Try running `xcode-select --install` instead to trigger the popup. If that doesn't work, you'll need to install the XCode development environment [from the App Store][]. After -installation, open up XCode and enter its preferences menu. Go to the "downloads" tab and install the +installation, open up XCode and enter its preferences menu. Go to the "downloads" tab and install the "command line tools" package. [from the App Store]: https://itunes.apple.com/us/app/xcode/id497799835 ## Install ARM GCC 4.9 series compiler -Cleanflight is built using the 4.9 series GCC compiler provided by the [GNU Tools for ARM Embedded Processors project][]. +INAV is built using the 4.9 series GCC compiler provided by the [GNU Tools for ARM Embedded Processors project][]. Hit the "all downloads" link on the right side of the GNU Tools for ARM page to view [the older releases][]. Grab the -Mac installation tarball for the latest version in the 4.9 series (e.g. 4.9-2015q2). Move it somewhere useful -such as a `~/development` folder (in your home directory) and double click it to unpack it. You should end up with a +Mac installation tarball for the latest version in the 4.9 series (e.g. 4.9-2015q2). Move it somewhere useful +such as a `~/development` folder (in your home directory) and double click it to unpack it. You should end up with a folder called `~/development/gcc-arm-none-eabi-4_9-2015q2/`. Now you just need to add the `bin/` directory from inside the GCC directory to your system's path. Run `nano ~/.profile`. Add a @@ -75,26 +75,26 @@ If `arm-none-eabi-gcc` couldn't be found, go back and check that you entered the ## Checkout CleanFlight sourcecode through git -Enter your development directory and clone the [Cleanflight repository][] using the "HTTPS clone URL" which is shown on -the right side of the Cleanflight GitHub page, like so: +Enter your development directory and clone the [INAV repository][] using the "HTTPS clone URL" which is shown on +the right side of the INAV GitHub page, like so: ``` git clone https://github.com/cleanflight/cleanflight.git ``` -This will download the entire Cleanflight repository for you into a new folder called "cleanflight". +This will download the entire INAV repository for you into a new folder called "cleanflight". [CleanFlight repository]: https://github.com/cleanflight/cleanflight ## Build the code Enter the cleanflight directory and run `make TARGET=NAZE` to build firmware for the Naze32. When the build completes, -the .hex firmware should be available as `obj/cleanflight_NAZE.hex` for you to flash using the Cleanflight +the .hex firmware should be available as `obj/cleanflight_NAZE.hex` for you to flash using the INAV Configurator. ## Updating to the latest source -If you want to erase your local changes and update to the latest version of the Cleanflight source, enter your +If you want to erase your local changes and update to the latest version of the INAV source, enter your cleanflight directory and run these commands to first erase your local changes, fetch and merge the latest changes from the repository, then rebuild the firmware: diff --git a/docs/development/Building in Ubuntu.md b/docs/development/Building in Ubuntu.md index d52e87c7d..428dce95e 100755 --- a/docs/development/Building in Ubuntu.md +++ b/docs/development/Building in Ubuntu.md @@ -1,7 +1,7 @@ # 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 +which they are downstreaming from Debian, is not compatible with INAV. We suggest that you take an alternative PPA from Terry Guo, found here: https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded @@ -50,7 +50,7 @@ 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 +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 @@ -58,7 +58,7 @@ $ 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. +You can use the INAV-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file. ## Bricked/Bad build? diff --git a/docs/development/Building in Windows.md b/docs/development/Building in Windows.md index bb0f144f8..a3dd1d2d3 100755 --- a/docs/development/Building in Windows.md +++ b/docs/development/Building in Windows.md @@ -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: @@ -65,7 +65,7 @@ git clone https://github.com/cleanflight/cleanflight.git ![GIT Checkout](assets/012.git_checkout.png) -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: ```bash cd cleanflight @@ -84,7 +84,7 @@ arm-none-eabi-size ./obj/main/cleanflight_NAZE.elf arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/cleanflight_NAZE.elf obj/cleanflight_NAZE.hex ``` -You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file. +You can use the INAV-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file. ## Updating and rebuilding diff --git a/docs/development/Development.md b/docs/development/Development.md index 3a97075cf..537d8316e 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -34,7 +34,7 @@ Ideally, there should be tests for any new code. However, since this is a legacy If you want to make changes and want to make sure it's tested then focus on the minimal set of changes required to add a test. -Tests currently live in the `test` folder and they use the google test framework. +Tests currently live in the `test` folder and they use the google test framework. The tests are compiled and run natively on your development machine and not on the target platform. This allows you to develop tests and code and actually execute it to make sure it works without needing a development board or simulator. @@ -74,7 +74,7 @@ https://help.github.com/articles/creating-a-pull-request/ The main flow for a contributing is as follows: -1. Login to github, go to the cleanflight repository and press `fork`. +1. Login to github, go to the INAV repository and press `fork`. 2. Then using the command line/terminal on your computer: `git clone ` 3. `cd cleanflight` 4. `git checkout master` @@ -95,8 +95,6 @@ Later, you can get the changes from the cleanflight repo into your `master` bran 3. `git fetch cleanflight` 4. `git merge cleanflight/master` 5. `git push origin master` is an optional step that will update your fork on github - - -You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual. +You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual. diff --git a/docs/development/Travis.md b/docs/development/Travis.md index f9c87ef33..169d06930 100644 --- a/docs/development/Travis.md +++ b/docs/development/Travis.md @@ -1,6 +1,6 @@ #Travis -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