Skip to content

Commit

Permalink
Merge pull request iNavFlight#5 from iNavFlight/master
Browse files Browse the repository at this point in the history
merge master
  • Loading branch information
UnchartedBull committed Sep 2, 2020
2 parents be055dc + 5967029 commit 90e9edb
Show file tree
Hide file tree
Showing 92 changed files with 2,511 additions and 369 deletions.
15 changes: 13 additions & 2 deletions docs/Rx.md
Expand Up @@ -95,9 +95,20 @@ Just connect the S.Port wire from the receiver to the TX pad of a free UART on y

#### Configuration

For INAV 2.6 and newer versions, the default configuration should just work. However, if you're
upgrading from a previous version you might need to set the following settings to their
default values:

```
set serialrx_inverted = OFF
set serialrx_halfduplex = AUTO
```

For INAV versions prior to 2.6, you need to change the following settings:

```
set serialrx_inverted = true
set serialrx_halfduplex = true
set serialrx_inverted = ON
set serialrx_halfduplex = ON
```

### XBUS
Expand Down
70 changes: 70 additions & 0 deletions docs/Safehomes.md
@@ -0,0 +1,70 @@
# INav - Safehomes

## Introduction

The "Home" position is used for the landing point when landing is enabled or in an emergency situation. It is usually determined by the GPS location where the aircraft is armed.

For airplanes, the landing procedure is explained very well by Pawel Spychalski [here.](https://quadmeup.com/inav-1-8-automated-landing-for-fixed-wings/)

<img src="https://quadmeup.com/wp-content/uploads/2017/06/fixed-wing-landing-1024x683.png" width="600">

One potential risk when landing is that there might be buildings, trees and other obstacles in the way as the airplance circles lower toward the ground at the arming point. Most people don't go the middle of the field when arming their airplanes.

## Safehome

Safehomes are a list of GPS coordinates that identify safe landing points. When the flight controller is armed, it checks the list of safehomes. The first one that is enabled and within 200m of the current position will be selected. Otherwise, it reverts to the old behaviour of using your current GPS position as home.

You can define up to 8 safehomes for different locations you fly at.

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.

## OSD Message when Armed

When the aircraft is armed, the OSD briefly shows `ARMED` and the current GPS position and current date and time.

If a safehome is selected, an additional message appears:
```
H - DIST -> SAFEHOME n <- New message
n is the Safehome index (0-7)
ARMED DIST is the distance from
GPS LATITUDE your current position to this safehome
GPS LONGITUDE
GPS PLUS CODE
CURRENT DATE
CURRENT TIME
```
The GPS details are those of the selected safehome.
To draw your attention to "HOME" being replaced, the message flashes and stays visible longer.

## CLI command `safehome` to manage safehomes

`safehome` - List all safehomes

`safehome reset` - Clears all safehomes.

`safehome <n> <enabled> <lat> <lon>` - Set the parameters of a safehome with index `<n>`.

Parameters:

* `<enabled>` - 0 is disabled, 1 is enabled.
* `<lat>` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789).
* `<lon>` - Longitude.

Safehomes are saved along with your regular settings and will appear in `diff` and `dump` output. Use `save` to save any changes, as with other settings.

### `safehome` example

```
# safehome
safehome 0 1 543533193 -45179273
safehome 1 1 435464846 -78654544
safehome 2 0 0 0
safehome 3 0 0 0
safehome 4 0 0 0
safehome 5 0 0 0
safehome 6 0 0 0
safehome 7 0 0 0
```

105 changes: 100 additions & 5 deletions docs/Settings.md

Large diffs are not rendered by default.

12 changes: 8 additions & 4 deletions make/release.mk
@@ -1,14 +1,14 @@
RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD

RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL
RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL
RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO
RELEASE_TARGETS += ALIENFLIGHTNGF7

RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4
RELEASE_TARGETS += BETAFLIGHTF4
RELEASE_TARGETS += FF_F35_LIGHTNING FF_FORTINIF4
RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV

RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL
RELEASE_TARGETS += SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL

RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2
Expand All @@ -21,7 +21,7 @@ RELEASE_TARGETS += MATEKF765

RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL FOXEERF722V2

RELEASE_TARGETS += SPEEDYBEEF4 FRSKYF3 FRSKYF4
RELEASE_TARGETS += SPEEDYBEEF4 SPEEDYBEEF7 FRSKYF3 FRSKYF4

RELEASE_TARGETS += NOX WINGFC

Expand All @@ -37,3 +37,7 @@ RELEASE_TARGETS += AIKONF4
RELEASE_TARGETS += ZEEZF7 HGLRCF722

RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411

RELEASE_TARGETS += ZEEZF7

RELEASE_TARGETS += FRSKYPILOT FRSKY_ROVERF7
1 change: 1 addition & 0 deletions make/source.mk
Expand Up @@ -129,6 +129,7 @@ MAIN_SRC = \
rx/crsf.c \
rx/eleres.c \
rx/fport.c \
rx/fport2.c \
rx/ibus.c \
rx/jetiexbus.c \
rx/msp.c \
Expand Down
8 changes: 4 additions & 4 deletions make/targets.mk
Expand Up @@ -72,13 +72,13 @@ $(error Unknown target MCU specified.)
endif

GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD
GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX
GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF4 PIKOBLX
GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX
GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT FRSKY_ROVERF7
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS))

## targets-group-1 : build some targets
Expand Down
4 changes: 2 additions & 2 deletions src/main/build/debug.h
Expand Up @@ -63,7 +63,6 @@ typedef enum {
DEBUG_REM_FLIGHT_TIME,
DEBUG_SMARTAUDIO,
DEBUG_ACC,
DEBUG_ITERM_RELAX,
DEBUG_ERPM,
DEBUG_RPM_FILTER,
DEBUG_RPM_FREQ,
Expand All @@ -72,7 +71,8 @@ typedef enum {
DEBUG_DYNAMIC_FILTER_FREQUENCY,
DEBUG_IRLOCK,
DEBUG_CD,
DEBUG_KALMAN,
DEBUG_KALMAN_GAIN,
DEBUG_PID_MEASUREMENT,
DEBUG_SPM_CELLS, // Smartport master FLVSS
DEBUG_SPM_VS600, // Smartport master VS600 VTX
DEBUG_SPM_VARIO, // Smartport master variometer
Expand Down
27 changes: 27 additions & 0 deletions src/main/cms/cms_menu_osd.c
Expand Up @@ -139,11 +139,38 @@ static long osdElemActionsOnEnter(const OSD_Entry *from)

#define OSD_ELEMENT_ENTRY(name, osd_item_id) OSD_ITEM_ENTRY(name, osd_item_id)

static const OSD_Entry menuCrsfRxEntries[]=
{
OSD_LABEL_ENTRY("-- CRSF RX --"),

OSD_SETTING_ENTRY("CRSF SNR LEVEL", SETTING_OSD_SNR_ALARM),
OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_CRSF_RSSI_DBM),
OSD_ELEMENT_ENTRY("RX LQ", OSD_CRSF_LQ),
OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_CRSF_SNR_DB),
OSD_ELEMENT_ENTRY("TX POWER", OSD_CRSF_TX_POWER),

OSD_BACK_AND_END_ENTRY,
};

const CMS_Menu cmsx_menuCrsf = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUCRF",
.GUARD_type = OME_MENU,
#endif
.onEnter = NULL,
.onExit = NULL,
.onGlobalExit = NULL,
.entries = menuCrsfRxEntries,
};

static const OSD_Entry menuOsdElemsEntries[] =
{
OSD_LABEL_ENTRY("--- OSD ITEMS ---"),

OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE),
#ifdef USE_SERIALRX_CRSF
OSD_SUBMENU_ENTRY("CRSF RX", &cmsx_menuCrsf),
#endif // CRSF Menu
OSD_ELEMENT_ENTRY("MAIN BATTERY", OSD_MAIN_BATT_VOLTAGE),
OSD_ELEMENT_ENTRY("MAIN BATT SC", OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE),
OSD_ELEMENT_ENTRY("CELL VOLTAGE", OSD_MAIN_BATT_CELL_VOLTAGE),
Expand Down
9 changes: 0 additions & 9 deletions src/main/common/maths.c
Expand Up @@ -142,15 +142,6 @@ int32_t applyDeadband(int32_t value, int32_t deadband)
return value;
}

float fapplyDeadbandf(float value, float deadband)
{
if (fabsf(value) < deadband) {
return 0;
}

return value >= 0 ? value - deadband : value + deadband;
}

int constrain(int amt, int low, int high)
{
if (amt < low)
Expand Down
1 change: 0 additions & 1 deletion src/main/common/maths.h
Expand Up @@ -130,7 +130,6 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu

int gcd(int num, int denom);
int32_t applyDeadband(int32_t value, int32_t deadband);
float fapplyDeadbandf(float value, float deadband);

int constrain(int amt, int low, int high);
float constrainf(float amt, float low, float high);
Expand Down
56 changes: 56 additions & 0 deletions src/main/common/tristate.h
@@ -0,0 +1,56 @@
/*
* This file is part of iNav.
*
* 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
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/

#pragma once

#include <stdbool.h>

// tristate_e represents something that can take a default AUTO
// value and two explicit ON and OFF values. To ease the transition
// from boolean settings (0 = OFF, 1 = ON), the 1 value has
// been picked as ON while OFF is represented by 2. AUTO is represented
// by 0.
typedef enum {
TRISTATE_AUTO = 0,
TRISTATE_ON = 1,
TRISTATE_OFF = 2,
} tristate_e;

// tristateWithDefaultOnIsActive returns false is tristate is TRISTATE_OFF
// and true otherwise.
static inline bool tristateWithDefaultOnIsActive(tristate_e tristate)
{
return tristate != TRISTATE_OFF;
}

// tristateWithDefaultOffIsActive returns true is tristate is TRISTATE_ON
// and false otherwise.
static inline bool tristateWithDefaultOffIsActive(tristate_e tristate)
{
return tristate == TRISTATE_ON;
}

// tristateWithDefaultIsActive() calls tristateWithDefaultOnIsActive() when
// def is true, and tristateWithDefaultOffIsActive() otherwise.
// See tristateWithDefaultOnIsActive() and tristateWithDefaultOffIsActive()
static inline bool tristateWithDefaultIsActive(tristate_e tristate, bool def)
{
return def ? tristateWithDefaultOnIsActive(tristate) : tristateWithDefaultOffIsActive(tristate);
}
3 changes: 2 additions & 1 deletion src/main/config/parameter_group_ids.h
Expand Up @@ -113,7 +113,8 @@
#define PG_GLOBAL_VARIABLE_CONFIG 1023
#define PG_SMARTPORT_MASTER_CONFIG 1024
#define PG_OSD_LAYOUTS_CONFIG 1025
#define PG_INAV_END 1025
#define PG_SAFE_HOME_CONFIG 1026
#define PG_INAV_END 1026

// OSD configuration (subject to change)
//#define PG_OSD_FONT_CONFIG 2047
Expand Down
3 changes: 3 additions & 0 deletions src/main/drivers/accgyro/accgyro_icm20689.c
Expand Up @@ -120,6 +120,9 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro)
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(busDev, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
#endif

// Switch SPI to fast speed
busSetSpeed(busDev, BUS_SPEED_FAST);
}

bool icm20689GyroDetect(gyroDev_t *gyro)
Expand Down
7 changes: 7 additions & 0 deletions src/main/drivers/flash.c
Expand Up @@ -287,6 +287,13 @@ void flashPartitionErase(flashPartition_t *partition)
{
const flashGeometry_t * const geometry = flashGetGeometry();

// if there's a single FLASHFS partition and it uses the entire flash then do a full erase
const bool doFullErase = (flashPartitionCount() == 1) && (FLASH_PARTITION_SECTOR_COUNT(partition) == geometry->sectors);
if (doFullErase) {
flashEraseCompletely();
return;
}

for (unsigned i = partition->startSector; i <= partition->endSector; i++) {
uint32_t flashAddress = geometry->sectorSize * i;
flashEraseSector(flashAddress);
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/max7456.c
Expand Up @@ -483,7 +483,7 @@ void max7456Write(uint8_t x, uint8_t y, const char *buff, uint8_t mode)
}
}

// Must be called with the lock held. Returns wether any new characters
// Must be called with the lock held. Returns whether any new characters
// were drawn.
static bool max7456DrawScreenPartial(void)
{
Expand Down
6 changes: 6 additions & 0 deletions src/main/drivers/osd_symbols.h
Expand Up @@ -240,6 +240,12 @@
#define SYM_HUD_ARROWS_D2 0x1AC // 428 2 arrows down
#define SYM_HUD_ARROWS_D3 0x1AD // 429 3 arrows down

#define SYM_2RSS 0xEA // RSSI 2
#define SYM_DB 0xEB // dB
#define SYM_DBM 0xEC // dBm
#define SYM_SRN 0xEE // SNR
#define SYM_MW 0xED // mW

#else

#define TEMP_SENSOR_SYM_COUNT 0
Expand Down
20 changes: 16 additions & 4 deletions src/main/drivers/pinio.c
Expand Up @@ -32,19 +32,31 @@
/*** Hardware definitions ***/
const pinioHardware_t pinioHardware[] = {
#if defined(PINIO1_PIN)
{ .ioTag = IO_TAG(PINIO1_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
#if !defined(PINIO1_FLAGS)
#define PINIO1_FLAGS 0
#endif
{ .ioTag = IO_TAG(PINIO1_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO1_FLAGS },
#endif

#if defined(PINIO2_PIN)
{ .ioTag = IO_TAG(PINIO2_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
#if !defined(PINIO2_FLAGS)
#define PINIO2_FLAGS 0
#endif
{ .ioTag = IO_TAG(PINIO2_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO2_FLAGS },
#endif

#if defined(PINIO3_PIN)
{ .ioTag = IO_TAG(PINIO3_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
#if !defined(PINIO3_FLAGS)
#define PINIO3_FLAGS 0
#endif
{ .ioTag = IO_TAG(PINIO3_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO3_FLAGS },
#endif

#if defined(PINIO4_PIN)
{ .ioTag = IO_TAG(PINIO4_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
#if !defined(PINIO4_FLAGS)
#define PINIO4_FLAGS 0
#endif
{ .ioTag = IO_TAG(PINIO4_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO4_FLAGS },
#endif
};

Expand Down

0 comments on commit 90e9edb

Please sign in to comment.