mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-13 03:19:58 +03:00
iNav to INAV
This commit is contained in:
parent
8ee6d5de72
commit
ef317763dd
72 changed files with 184 additions and 184 deletions
6
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
6
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
|
@ -9,9 +9,9 @@ assignees: ''
|
|||
|
||||
**PLEASE MAKE SURE YOU READ AND UNDERSTAND THE SOCIAL MEDIA SUPPORT CHANNELS. QUESTIONS ABOUT FLASHING, CONFIGURING, PILOTING MAY BE CLOSED WITHOUT FURTHER INTERACTION.**
|
||||
|
||||
* [Telegram channel](https://t.me/INAVFlight)
|
||||
* [Facebook group](https://www.facebook.com/groups/INAVOfficial)
|
||||
* [RC Groups thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-%28navigation-rewrite%29-project)
|
||||
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
|
||||
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
||||
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||
|
||||
**Please double-check that nobody reported the issue before by using search in this bug tracker.**
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ Users of OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use IN
|
|||
|
||||
### OSD layout Copy, Move, or Replace helper tool
|
||||
|
||||
[Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in iNav. Choose the from and to OSD layouts, and the method of transfering the layouts.
|
||||
[Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in INAV. Choose the from and to OSD layouts, and the method of transfering the layouts.
|
||||
|
||||
## Installation
|
||||
|
||||
|
|
|
@ -242,7 +242,7 @@ set vbat_min_cell_voltage = 250
|
|||
|
||||
#### Simple example with automatic profile switching
|
||||
|
||||
In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the iNav defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD.
|
||||
In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the INAV defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD.
|
||||
|
||||
```
|
||||
feature BAT_PROF_AUTOSWITCH
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. With multirotors, the motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended).
|
||||
|
||||
Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in iNav 2.2)
|
||||
Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in INAV 2.2)
|
||||
|
||||
**YAW STICK ARMING OVERRIDE:**
|
||||
Arming is disabled when Nav modes are configured and no GPS lock is available or if a WP mission is loaded but the first WP is farther than the `nav_wp_safe_distance` setting. This Arming block can be bypassed if need be by setting `nav_extra_arming_safety` to `ALLOW_BYPASS` and moving the Yaw stick to the high position when the Arm switch is used. This bypasses GPS Arm blocking pre INAV 4.0.0 and both GPS and "First WP too far" Arm blocking from INAV 4.0.0.
|
||||
|
@ -80,7 +80,7 @@ For tricopters, you may want to retain the ability to yaw while on the ground, s
|
|||
|
||||
## Throttle settings and their interaction
|
||||
|
||||
*Terminology. After iNav 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.*
|
||||
*Terminology. After INAV 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.*
|
||||
|
||||
`min_command` -
|
||||
With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# Display
|
||||
|
||||
INAV supports displays to provide information to you about your aircraft and iNav state.
|
||||
INAV supports displays to provide information to you about your aircraft and INAV state.
|
||||
|
||||
When the aircraft is armed, an "Armed" message is displayed. When it is disarmed, a summary page is displayed. Page cycling has been removed and no other information is currently available
|
||||
|
||||
|
|
|
@ -19,7 +19,7 @@ the actual one measured by the gyroscopes, and the controller tries to bring thi
|
|||
Note that:
|
||||
|
||||
* For fixed wing, a PIFF controller is used. Some documentation is available in the wiki and legacy release notes.
|
||||
* The iNav Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine.
|
||||
* The INAV Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine.
|
||||
|
||||
## PIDs
|
||||
|
||||
|
|
|
@ -27,4 +27,4 @@ I2C solutions like `VL53L0X` or `INAV_I2C` can be connected to I2C port and used
|
|||
|
||||
#### Constraints
|
||||
|
||||
iNav does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
|
||||
INAV does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
|
|
@ -47,7 +47,7 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118
|
|||
|
||||
#### Spektrum pesudo RSSI
|
||||
|
||||
As of iNav 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal iNav RSSI (0-1023 range). In order to use this feature, the following is necessary:
|
||||
As of INAV 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal INAV RSSI (0-1023 range). In order to use this feature, the following is necessary:
|
||||
|
||||
* Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient.
|
||||
* The CLI variable `rssi_channel` is set to channel 9:
|
||||
|
|
|
@ -20,7 +20,7 @@ The safehome operating mode is set using ```safehome_usage_mode```. If ```OFF``
|
|||
|
||||
If you frequently use RTH to return back to the arming point, you may not want the aircraft to fly to the safehome. Let it do this at least once to confirm safehomes is working as expected. Afterward, `set safehome_usage_mode = RTH_FS` and the safehome will only be used for failsafe.
|
||||
|
||||
When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the iNav failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions.
|
||||
When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the INAV failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions.
|
||||
|
||||
When you are choosing safehome locations, ensure that the location is clear of obstructions for a radius more than 50m (`nav_fw_loiter_radius`). As the plane descends, the circles aren't always symmetrical, as wind direction could result in some wider or tighter turns. Also, the direction and length of the final landing stage is also unknown. You want to choose a point that has provides a margin for variation and the final landing.
|
||||
|
||||
|
|
|
@ -1924,7 +1924,7 @@ _// TODO_
|
|||
|
||||
### inav_use_gps_velned
|
||||
|
||||
Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance.
|
||||
Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
@ -2824,7 +2824,7 @@ Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no speci
|
|||
|
||||
### nav_disarm_on_landing
|
||||
|
||||
If set to ON, iNav disarms the FC after landing
|
||||
If set to ON, INAV disarms the FC after landing
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
@ -5934,7 +5934,7 @@ VTX RF power level to use. The exact number of mw depends on the VTX hardware.
|
|||
|
||||
### vtx_smartaudio_alternate_softserial_method
|
||||
|
||||
Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier.
|
||||
Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
|
|
@ -212,7 +212,7 @@ The INAV implementation of LTM implements the following frames:
|
|||
* S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item suffixed '+' not implemented in INAV.
|
||||
* O-FRAME: Origin (home position, lat, long, altitude, fix)
|
||||
|
||||
In addition, in iNav:
|
||||
In addition, in INAV:
|
||||
|
||||
* N-FRAME: Navigation information (GPS mode, Nav mode, Nav action, Waypoint number, Nav Error, Nav Flags).
|
||||
* X-FRAME: Extra information. Currently HDOP is reported.
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
## Overview
|
||||
|
||||
iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card).
|
||||
INAV (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card).
|
||||
|
||||
When MSC mode is used with **internal flash** there are a few differences compared to **SD card** as it's a virtual file system:
|
||||
|
||||
|
@ -62,7 +62,7 @@ $ md5sum /tmp/{msc,sdc}logs/LOG00035.TXT
|
|||
7cd259777ba4f29ecbde2f76882b1840 /tmp/msclogs/LOG00035.TXT
|
||||
7cd259777ba4f29ecbde2f76882b1840 /tmp/sdclogs/LOG00035.TXT
|
||||
```
|
||||
You should also be able to run blackbox utilities (e.g. the iNav specific `blackbox_decode`) without errors on the files, e.g.
|
||||
You should also be able to run blackbox utilities (e.g. the INAV specific `blackbox_decode`) without errors on the files, e.g.
|
||||
|
||||
```
|
||||
$ blackbox_decode --stdout --merge-gps > /dev/null /tmp/msclogs/LOG00035.TXT
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# Wireless connections
|
||||
|
||||
From iNav 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP).
|
||||
From INAV 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP).
|
||||
|
||||
## BLE
|
||||
|
||||
|
@ -13,7 +13,7 @@ The following adapters are supported:
|
|||
Flightcontrollers with BLE should also work, if you have an adapter/FC that doesn't work, open an issue here on Github and we will add it.
|
||||
|
||||
### Configuring the BLE modules
|
||||
Activate MSP in iNav on a free UART port and set the Bluetooth module to the appropriate baud rate.
|
||||
Activate MSP in INAV on a free UART port and set the Bluetooth module to the appropriate baud rate.
|
||||
|
||||
Example for a HM-10 module:
|
||||
|
||||
|
@ -22,7 +22,7 @@ Standard baud rate is 115200 baud, CR+LF
|
|||
|
||||
```
|
||||
AT+BAUD4
|
||||
AT+NAMEiNav
|
||||
AT+NAMEINAV
|
||||
```
|
||||
|
||||
The baud rate values:
|
||||
|
@ -46,8 +46,8 @@ Allows connections via Wifi.
|
|||
|
||||
Hardware:
|
||||
- DIY, ESP8266 based:
|
||||
This project can be used to make iNav Wifi enabled: https://github.com/Scavanger/MSPWifiBridge
|
||||
This project can be used to make INAV Wifi enabled: https://github.com/Scavanger/MSPWifiBridge
|
||||
A small ESP01S module should still fit anywhere.
|
||||
|
||||
- ExpressLRS Wifi:
|
||||
Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in iNav.
|
||||
Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in INAV.
|
||||
|
|
|
@ -44,7 +44,7 @@ Due to differences on the board (I2C - see below), there are two firmware varian
|
|||
### I2C
|
||||
|
||||
The F405-AIO, STD, CTR boards expose dedicated I2C pads.
|
||||
The F405-OSD does not expose I2C. For iNav there is a software I2C provision using the USART3 pads, as:
|
||||
The F405-OSD does not expose I2C. For INAV there is a software I2C provision using the USART3 pads, as:
|
||||
|
||||
* SDA => RX3, SCL => TX3
|
||||
* Do not assign any serial function to USART3
|
||||
|
|
|
@ -31,7 +31,7 @@ Then follow this : https://pixhawk.org/dev/bootloader_update
|
|||
|
||||
### Interface and Ports
|
||||
|
||||
Total UARTS Recognized by iNav -> 8
|
||||
Total UARTS Recognized by INAV -> 8
|
||||
|
||||
#### USART1
|
||||
* Location : Top
|
||||
|
|
|
@ -14,7 +14,7 @@ Download and install Vagrant for you OS from here:
|
|||
https://www.vagrantup.com/downloads.html
|
||||
```
|
||||
|
||||
## Cloning iNav repository
|
||||
## Cloning INAV repository
|
||||
Using git (The preferred way!)
|
||||
```
|
||||
git clone https://github.com/iNavFlight/inav.git
|
||||
|
@ -28,7 +28,7 @@ and extract it to folder of your choosing.
|
|||
|
||||
## Running the virtual machine
|
||||
Open up a terminal or command line interface (In windows search for CMD.exe and run it as administrator!)
|
||||
Navigate in to the directory of your cloned/unzipped iNav repository. (Where the "Vagrantfile" is located.) and start the virtual machine.
|
||||
Navigate in to the directory of your cloned/unzipped INAV repository. (Where the "Vagrantfile" is located.) and start the virtual machine.
|
||||
```
|
||||
vagrant up
|
||||
```
|
||||
|
|
|
@ -32,9 +32,9 @@ Install python and python-yaml to allow updates to settings.md
|
|||
|
||||
To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71)
|
||||
|
||||
## Downloading the iNav repository (example):
|
||||
## Downloading the INAV repository (example):
|
||||
|
||||
Mount MS windows C drive and clone iNav
|
||||
Mount MS windows C drive and clone INAV
|
||||
1. `cd /mnt/c`
|
||||
1. `git clone https://github.com/iNavFlight/inav.git`
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!-- XSchema for MW / iNav missions
|
||||
This file is part of inav
|
||||
<!-- XSchema for MW / INAV missions
|
||||
This file is part of INAV
|
||||
usage e.g. xmllint --noout --schema mw-mission.xsd example.mission
|
||||
Updated 2021-11-12 for 'meta' substitution.
|
||||
-->
|
||||
|
|
|
@ -10,7 +10,7 @@ Please search for existing issues *before* creating new ones.
|
|||
|
||||
When submitting an issue the general rule is to include:
|
||||
|
||||
1. What is your setup and a detailed explanation of the issue, also include last working version of iNav.
|
||||
1. What is your setup and a detailed explanation of the issue, also include last working version of INAV.
|
||||
1. status dump from cli.
|
||||
1. bootlog dump from cli.
|
||||
1. dump dump from cli.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -23,9 +23,9 @@
|
|||
#define PG_MOTOR_MIXER 4
|
||||
#define PG_BLACKBOX_CONFIG 5
|
||||
#define PG_MOTOR_CONFIG 6
|
||||
//#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in iNav
|
||||
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav
|
||||
//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav
|
||||
//#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in INAV
|
||||
//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in INAV
|
||||
//#define PG_SENSOR_TRIMS 9 -- NOT USED in INAV
|
||||
#define PG_GYRO_CONFIG 10
|
||||
#define PG_BATTERY_PROFILES 11
|
||||
#define PG_CONTROL_RATE_PROFILES 12
|
||||
|
@ -85,7 +85,7 @@
|
|||
// cleanflight v2 specific parameter group ids start at 256
|
||||
#define PG_VTX_SETTINGS_CONFIG 259
|
||||
|
||||
// iNav specific parameter group ids start at 1000
|
||||
// INAV specific parameter group ids start at 1000
|
||||
#define PG_INAV_START 1000
|
||||
#define PG_PITOTMETER_CONFIG 1000
|
||||
#define PG_POSITION_ESTIMATION_CONFIG 1001
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
|
@ -18,7 +18,7 @@
|
|||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* BMP388 Driver author: Dominic Clifton
|
||||
* iNav port: Michel Pastor
|
||||
* INAV port: Michel Pastor
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute
|
||||
* INAV is free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it
|
||||
* INAV is distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute
|
||||
* INAV is free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it
|
||||
* INAV is distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav are free software. You can redistribute
|
||||
* INAV are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav are distributed in the hope that they
|
||||
* INAV are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav are free software. You can redistribute
|
||||
* INAV are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav are distributed in the hope that they
|
||||
* INAV are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav free software. You can redistribute
|
||||
* INAV free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav distributed in the hope that it
|
||||
* INAV distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
/*
|
||||
* Cleanflight (or Baseflight): original
|
||||
* jflyper: Mono-timer and single-wire half-duplex
|
||||
* jflyper: Ported to iNav
|
||||
* jflyper: Ported to INAV
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav
|
||||
* This file is part of INAV
|
||||
*
|
||||
* iNav is free software. You can redistribute
|
||||
* INAV is free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it
|
||||
* INAV is distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav
|
||||
* This file is part of INAV
|
||||
*
|
||||
* iNav free software. You can redistribute
|
||||
* INAV free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav distributed in the hope that it
|
||||
* INAV distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -2268,7 +2268,7 @@ groups:
|
|||
min: 0
|
||||
max: 255
|
||||
- name: inav_use_gps_velned
|
||||
description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance."
|
||||
description: "Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance."
|
||||
default_value: ON
|
||||
field: use_gps_velned
|
||||
type: bool
|
||||
|
@ -2388,7 +2388,7 @@ groups:
|
|||
headers: ["navigation/navigation.h"]
|
||||
members:
|
||||
- name: nav_disarm_on_landing
|
||||
description: "If set to ON, iNav disarms the FC after landing"
|
||||
description: "If set to ON, INAV disarms the FC after landing"
|
||||
default_value: OFF
|
||||
field: general.flags.disarm_on_landing
|
||||
type: bool
|
||||
|
@ -3721,7 +3721,7 @@ groups:
|
|||
field: smartAudioEarlyAkkWorkaroundEnable
|
||||
type: bool
|
||||
- name: vtx_smartaudio_alternate_softserial_method
|
||||
description: "Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier."
|
||||
description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier."
|
||||
default_value: ON
|
||||
field: smartAudioAltSoftSerialMethod
|
||||
type: bool
|
||||
|
|
|
@ -948,7 +948,7 @@ float pidHeadingHold(float dT)
|
|||
- output
|
||||
- that gives about 2 seconds to correct any error, no matter how big. Of course, usually more because of inertia.
|
||||
That was making him quite "soft" for small changes and rapid for big ones that started to appear
|
||||
when iNav introduced real RTH and WAYPOINT that might require rapid heading changes.
|
||||
when INAV introduced real RTH and WAYPOINT that might require rapid heading changes.
|
||||
|
||||
New approach uses modified principle:
|
||||
- manual yaw rate is not used. MAG_HOLD is decoupled from manual input settings
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav
|
||||
* This file is part of INAV
|
||||
*
|
||||
* iNav free software. You can redistribute
|
||||
* INAV free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav distributed in the hope that it
|
||||
* INAV distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav
|
||||
* This file is part of INAV
|
||||
*
|
||||
* iNav free software. You can redistribute
|
||||
* INAV free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav distributed in the hope that it
|
||||
* INAV is distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -324,7 +324,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
|||
//zero is indeed a valid power level to set the vtx to, but it activates pit mode.
|
||||
//crucially, after sending 0 dbm, the vtx does NOT report its power level to be 0 dbm.
|
||||
//instead, it reports whatever value was set previously and it reports to be in pit mode.
|
||||
//for this reason, zero shouldn't be used as a normal power level in iNav.
|
||||
//for this reason, zero shouldn't be used as a normal power level in INAV.
|
||||
for (int8_t i = 0; i < saPowerCount; i++ ) {
|
||||
saPowerTable[i].dbi = buf[9 + i + 1]; //+ 1 to skip the first power level, as mentioned above
|
||||
saPowerTable[i].mW = saDbiToMw(saPowerTable[i].dbi);
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
static const char autorun_file[] =
|
||||
"[autorun]\r\n"
|
||||
"icon=icon.ico\r\n"
|
||||
"label=iNav Onboard Flash\r\n" ;
|
||||
"label=INAV Onboard Flash\r\n" ;
|
||||
#define AUTORUN_SIZE (sizeof(autorun_file) - 1)
|
||||
#define EMFAT_INCR_AUTORUN 1
|
||||
#else
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// iNav specific IDs start from 0x2000
|
||||
// INAV specific IDs start from 0x2000
|
||||
// See https://github.com/iNavFlight/inav/wiki/MSP-V2#msp-v2-message-catalogue
|
||||
|
||||
#define MSP2_INAV_STATUS 0x2000
|
||||
|
|
|
@ -96,9 +96,9 @@ typedef struct navigationFlags_s {
|
|||
bool isAdjustingHeading;
|
||||
|
||||
// Behaviour modifiers
|
||||
bool isGCSAssistedNavigationEnabled; // Does iNav accept WP#255 - follow-me etc.
|
||||
bool isGCSAssistedNavigationEnabled; // Does INAV accept WP#255 - follow-me etc.
|
||||
bool isGCSAssistedNavigationReset; // GCS control was disabled - indicate that so code could take action accordingly
|
||||
bool isTerrainFollowEnabled; // Does iNav use rangefinder for terrain following (adjusting baro altitude target according to rangefinders readings)
|
||||
bool isTerrainFollowEnabled; // Does INAV use rangefinder for terrain following (adjusting baro altitude target according to rangefinders readings)
|
||||
|
||||
// Failsafe actions
|
||||
bool forcedRTHActivated;
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav are free software. You can redistribute
|
||||
* INAV are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it
|
||||
* INAV is distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav
|
||||
* This file is part of INAV
|
||||
*
|
||||
* iNav free software. You can redistribute
|
||||
* INAV free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav distributed in the hope that it
|
||||
* INAV distributed in the hope that it
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "stdbool.h"
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -6,7 +6,7 @@ will be available at: http://furiousfpv.com
|
|||
- Rugged & Robust Aluminum Case for Maximum Crash Protection
|
||||
- Exclusively Designed for INAV Firmware
|
||||
- Ultra Simplistic to Install with Standing USB Ports & Pads
|
||||
- Fully Supported iNav Firmware
|
||||
- Fully Supported INAV Firmware
|
||||
- Integrated OSD for Maximum Data Feedback
|
||||
- Built In Camera & VTx Port with Peripheral Pass
|
||||
- Maximum (6) Port UART Layout
|
||||
|
|
|
@ -199,7 +199,7 @@
|
|||
|
||||
#ifdef FRSKYPILOT_LED
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA1 // S10 pad for iNav
|
||||
#define WS2811_PIN PA1 // S10 pad for INAV
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 9
|
||||
#else
|
||||
|
|
|
@ -183,7 +183,7 @@
|
|||
#define CURRENT_METER_SCALE 179
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA15 // S5 pad for iNav
|
||||
#define WS2811_PIN PA15 // S5 pad for INAV
|
||||
|
||||
#define USE_SPEKTRUM_BIND
|
||||
#define BIND_PIN PA3 // RX2
|
||||
|
|
|
@ -17,5 +17,5 @@
|
|||
## Warnings
|
||||
|
||||
* PicRacers native Flight controller (PX4 & ArduPilot) motor layout is different to iNAV
|
||||
* Either Swap your ESC PWM cables to match iNav
|
||||
* Either Swap your ESC PWM cables to match INAV
|
||||
* Or make a custom mix
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software: you can redistribute it and/or modify
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that it will be useful,
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with iNav. If not, see <http://www.gnu.org/licenses/>.
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* INAV is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* INAV is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
|
|
|
@ -65,7 +65,7 @@ typedef enum {
|
|||
LTM_MODE_FLYBYWIRE2,
|
||||
LTM_MODE_CRUISE,
|
||||
LTM_MODE_UNKNOWN,
|
||||
// iNav specific extensions
|
||||
// INAV specific extensions
|
||||
LTM_MODE_LAUNCH,
|
||||
LTM_MODE_AUTOTUNE
|
||||
} ltm_modes_e;
|
||||
|
|
|
@ -1,15 +1,15 @@
|
|||
#!/usr/bin/env ruby
|
||||
|
||||
##
|
||||
## This file is part of iNav.
|
||||
## This file is part of INAV.
|
||||
##
|
||||
## iNav is free software. You can redistribute this software
|
||||
## INAV is free software. You can redistribute this software
|
||||
## and/or modify this software under the terms of the
|
||||
## GNU General Public License as published by the Free Software
|
||||
## Foundation, either version 3 of the License, or (at your option)
|
||||
## any later version.
|
||||
##
|
||||
## iNav is distributed in the hope that they will be
|
||||
## INAV is distributed in the hope that they will be
|
||||
## useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
## warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
## See the GNU General Public License for more details.
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
##
|
||||
## This file is part of iNav.
|
||||
## This file is part of INAV.
|
||||
##
|
||||
## iNav is free software. You can redistribute this software
|
||||
## INAV is free software. You can redistribute this software
|
||||
## and/or modify this software under the terms of the
|
||||
## GNU General Public License as published by the Free Software
|
||||
## Foundation, either version 3 of the License, or (at your option)
|
||||
## any later version.
|
||||
##
|
||||
## iNav is distributed in the hope that they will be
|
||||
## INAV is distributed in the hope that they will be
|
||||
## useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
## warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
## See the GNU General Public License for more details.
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue