1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 17:55:28 +03:00

Merge branch 'master' of https://github.com/RomanLut/inav into submit-gps-fix-estimation

This commit is contained in:
Roman Lut 2022-12-28 04:28:21 +02:00
commit 731b16c37d
25 changed files with 1129 additions and 122 deletions

View file

@ -1,14 +1,19 @@
FROM ubuntu:focal
ARG USER_ID
ARG GROUP_ID
ENV DEBIAN_FRONTEND noninteractive
RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip
RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi
RUN pip install pyyaml
RUN useradd inav
# if either of these are already set the same as the user's machine, leave them be and ignore the error
RUN addgroup --gid $GROUP_ID users; exit 0;
RUN adduser --disabled-password --gecos '' --uid $USER_ID --gid $GROUP_ID user; exit 0;
USER inav
USER user
RUN git config --global --add safe.directory /src
VOLUME /src

View file

@ -21,19 +21,29 @@ fi
if [ -z "$(docker images -q inav-build)" ]; then
echo -e "*** Building image\n"
docker build -t inav-build .
docker build -t inav-build --build-arg USER_ID="$(id -u)" --build-arg GROUP_ID="$(id -g)" .
echo -ne "\n"
fi
if [ ! -d ./build ]; then
echo -e "*** Creating build directory\n"
mkdir ./build
mkdir ./build && chmod 777 ./build
fi
if [ ! -d ./downloads ]; then
echo -e "*** Creating downloads directory\n"
mkdir ./downloads && chmod 777 ./downloads
fi
if [ ! -d ./tools ]; then
echo -e "*** Creating tools directory\n"
mkdir ./tools && chmod 777 ./tools
fi
echo -e "*** Building targets [$@]\n"
docker run --rm -it -v "$(pwd)":/src inav-build $@
if ls ./build/*.hex &> /dev/null; then
if [ -z "$(ls ./build/*.hex &> /dev/null)" ]; then
echo -e "\n*** Built targets in ./build:"
stat -c "%n (%.19y)" ./build/*.hex
fi

View file

@ -0,0 +1,46 @@
# Betaflight 4.3 compatible MSP DisplayPort OSD (DJI O3 "Canvas Mode")
INAV 6.0 includes a special mode for MSP DisplayPort that supports incomplete implementations of MSP DisplayPort that only support BetaFlight, like the DJI O3 Air Unit.
Different flight controllers have different OSD symbols and elements and require different fonts. BetaFlight's font is a single page and supports a maximum of 256 glyphs, INAV's font is currently 2 pages and supports up to 512 different glyphs.
While there is some overlap between the glyphs in BetaFlight and INAV, it is not possible to perform a 1 to 1 mapping for all the them. In cases where there is no suitable glyph in the BetaFlight font, a question mark `?` will be displayed.
This mode can be enabled by selecting BF43COMPAT as video format in the OSD tab of the configurator or by typing the following command on the CLI:
`set osd_video_system = BF43COMPAT`
## Limitations
* Canvas size is limited to PAL's canvas size.
* Unsupported Glyphs show up as `?`
## FAQ
### I see a lot of `?` on my OSD.
That is expected, when your INAV OSD widgets use glyphs that don't have a suitable mapping in BetaFlight's font.
### Does it work with the G2 and Original Air Unit/Vista?
Yes.
### Is this a replacement for WTFOS?
Not exactly. WTFOS is a full implementation of MSP-Displayport for rooted Air Unit/Vista/Googles V2 and actually works much better than BetaFlight compatibility mode, being able to display all INAV's glyphs.
### Can INAV fix DJI's product?
No. OSD renderinng happens on the googles/air unit side of things. Please ask DJI to fix their incomplete MSP DisplayPort implemenation. You can probably request it in [DJI's forum](https://forum.dji.com/forum.php?mod=forumdisplay&fid=129&filter=typeid&typeid=767).
### BetaFlight X.Y now has more symbols, can you update INAV?
Maybe. If a future version of BetaFlight includes more Glyphs that can be mapped into INAV it is fairly simple to add the mapping, but the problem with DJI's implemenation persists. Even if we update the mapping, if DJI does not update the fonts on their side the problem will persist.
### Can you replace glyph `X` with text `x description`?
While it might technically be possible to replace some glyphs with text in multiple cells, it will introduce a lot of complexity in the OSD rendering and configuration for something we hope is a temporary workaround.
### Does DJI support Canvas Mode?
Actually, no. What DJI calls Canvas Mode is actually MSP DisplayPort and is a character based OSD.

View file

@ -169,3 +169,5 @@ wp 12 0 0 0 0 0 0 0 0
...
wp 59 0 0 0 0 0 0 0 0
```
### Changing Mission-Index in flight
The MISSION CHANGE mode allows to switch between multiple stored missions in flight. With mode active the required mission index can be selected by cycling through missions using the WP mode switch. Selected mission is loaded when mission change mode is switched off. Mission index can also be changed through addition of a new Mission Index adjustment function which should be useful for DJI users unable to use the normal OSD mission related fields.

View file

@ -4724,7 +4724,7 @@ IMPERIAL, METRIC, UK
### osd_video_system
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO` and 'DJIWTF'
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, `DJIWTF` and `BF43COMPAT`
| Default | Min | Max |
| --- | --- | --- |

View file

@ -2,6 +2,10 @@
![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png)
# INAV 6 Horizon Hawk feature freeze
> INAV 6 feature freeze will happen on 29th of January 2023. No new features for INAv 6 will be accepted after that date.
# INAV Community
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)

View file

@ -476,6 +476,8 @@ main_sources(COMMON_SRC
io/displayport_max7456.h
io/displayport_msp.c
io/displayport_msp.h
io/displayport_msp_bf_compat.c
io/displayport_msp_bf_compat.h
io/displayport_oled.c
io/displayport_oled.h
io/displayport_msp_osd.c

View file

@ -47,7 +47,8 @@ typedef enum {
VIDEO_SYSTEM_PAL,
VIDEO_SYSTEM_NTSC,
VIDEO_SYSTEM_HDZERO,
VIDEO_SYSTEM_DJIWTF
VIDEO_SYSTEM_DJIWTF,
VIDEO_SYSTEM_BFCOMPAT
} videoSystem_e;
typedef enum {

View file

@ -1529,6 +1529,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
return true;
}
#ifdef USE_SAFE_HOME
static mspResult_e mspFcSafeHomeOutCommand(sbuf_t *dst, sbuf_t *src)
{
const uint8_t safe_home_no = sbufReadU8(src); // get the home number
@ -1542,6 +1543,8 @@ static mspResult_e mspFcSafeHomeOutCommand(sbuf_t *dst, sbuf_t *src)
return MSP_RESULT_ERROR;
}
}
#endif
static mspResult_e mspFcLogicConditionCommand(sbuf_t *dst, sbuf_t *src) {
const uint8_t idx = sbufReadU8(src);
@ -2919,6 +2922,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
return MSP_RESULT_ERROR; // will only be reached if the rollback is not ready
break;
#endif
#ifdef USE_SAFE_HOME
case MSP2_INAV_SET_SAFEHOME:
if (dataSize == 10) {
uint8_t i;
@ -2932,6 +2936,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
return MSP_RESULT_ERROR;
}
break;
#endif
default:
return MSP_RESULT_ERROR;
@ -3377,9 +3382,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = mspFcLogicConditionCommand(dst, src);
break;
#endif
#ifdef USE_SAFE_HOME
case MSP2_INAV_SAFEHOME:
*ret = mspFcSafeHomeOutCommand(dst, src);
break;
#endif
#ifdef USE_SIMULATOR
case MSP_SIMULATOR:

View file

@ -36,7 +36,7 @@ const char *armingDisableFlagNames[]= {
"FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS",
"ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX",
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM",
"SETTINGFAIL", "PWMOUT", "NOPREARM", "DSHOTBEEPER"
"SETTINGFAIL", "PWMOUT", "NOPREARM", "DSHOTBEEPER", "LANDED"
};
#endif

View file

@ -72,7 +72,7 @@ tables:
values: ["BATTERY", "CELL"]
enum: osd_stats_min_voltage_unit_e
- name: osd_video_system
values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF"]
values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "BF43COMPAT"]
enum: videoSystem_e
- name: osd_telemetry
values: ["OFF", "ON","TEST"]
@ -3025,7 +3025,7 @@ groups:
type: uint8_t
default_value: "OFF"
- name: osd_video_system
description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO` and 'DJIWTF'"
description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, `DJIWTF` and `BF43COMPAT`"
default_value: "AUTO"
table: osd_video_system
field: video_system

View file

@ -0,0 +1,163 @@
/* @file max7456_symbols.h
* @brief max7456 symbols for the mwosd font set
*
* @author Nathan Tsoi nathan@vertile.com
*
* Copyright (C) 2016 Nathan Tsoi
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>
*/
#pragma once
//Misc
#define BF_SYM_NONE 0x00
#define BF_SYM_END_OF_FONT 0xFF
#define BF_SYM_BLANK 0x20
#define BF_SYM_HYPHEN 0x2D
#define BF_SYM_BBLOG 0x10
#define BF_SYM_HOMEFLAG 0x11
//#define SYM_RPM 0x12
#define BF_SYM_ROLL 0x14
#define BF_SYM_PITCH 0x15
#define BF_SYM_TEMPERATURE 0x7A
// GPS and navigation
#define BF_SYM_LAT 0x89
#define BF_SYM_LON 0x98
#define BF_SYM_ALTITUDE 0x7F
#define BF_SYM_TOTAL_DISTANCE 0x71
#define BF_SYM_OVER_HOME 0x05
// RSSI
#define BF_SYM_RSSI 0x01
#define BF_SYM_LINK_QUALITY 0x7B
// Throttle Position (%)
#define BF_SYM_THR 0x04
// Unit Icons (Metric)
#define BF_SYM_M 0x0C
#define BF_SYM_KM 0x7D
#define BF_SYM_C 0x0E
// Unit Icons (Imperial)
#define BF_SYM_FT 0x0F
#define BF_SYM_MILES 0x7E
#define BF_SYM_F 0x0D
// Heading Graphics
#define BF_SYM_HEADING_N 0x18
#define BF_SYM_HEADING_S 0x19
#define BF_SYM_HEADING_E 0x1A
#define BF_SYM_HEADING_W 0x1B
#define BF_SYM_HEADING_DIVIDED_LINE 0x1C
#define BF_SYM_HEADING_LINE 0x1D
// AH Center screen Graphics
#define BF_SYM_AH_CENTER_LINE 0x72
#define BF_SYM_AH_CENTER 0x73
#define BF_SYM_AH_CENTER_LINE_RIGHT 0x74
#define BF_SYM_AH_RIGHT 0x02
#define BF_SYM_AH_LEFT 0x03
#define BF_SYM_AH_DECORATION 0x13
// Satellite Graphics
#define BF_SYM_SAT_L 0x1E
#define BF_SYM_SAT_R 0x1F
// Direction arrows
#define BF_SYM_ARROW_SOUTH 0x60
#define BF_SYM_ARROW_2 0x61
#define BF_SYM_ARROW_3 0x62
#define BF_SYM_ARROW_4 0x63
#define BF_SYM_ARROW_EAST 0x64
#define BF_SYM_ARROW_6 0x65
#define BF_SYM_ARROW_7 0x66
#define BF_SYM_ARROW_8 0x67
#define BF_SYM_ARROW_NORTH 0x68
#define BF_SYM_ARROW_10 0x69
#define BF_SYM_ARROW_11 0x6A
#define BF_SYM_ARROW_12 0x6B
#define BF_SYM_ARROW_WEST 0x6C
#define BF_SYM_ARROW_14 0x6D
#define BF_SYM_ARROW_15 0x6E
#define BF_SYM_ARROW_16 0x6F
#define BF_SYM_ARROW_SMALL_UP 0x75
#define BF_SYM_ARROW_SMALL_DOWN 0x76
// AH Bars
#define BF_SYM_AH_BAR9_0 0x80
#define BF_SYM_AH_BAR9_1 0x81
#define BF_SYM_AH_BAR9_2 0x82
#define BF_SYM_AH_BAR9_3 0x83
#define BF_SYM_AH_BAR9_4 0x84
#define BF_SYM_AH_BAR9_5 0x85
#define BF_SYM_AH_BAR9_6 0x86
#define BF_SYM_AH_BAR9_7 0x87
#define BF_SYM_AH_BAR9_8 0x88
// Progress bar
#define BF_SYM_PB_START 0x8A
#define BF_SYM_PB_FULL 0x8B
#define BF_SYM_PB_HALF 0x8C
#define BF_SYM_PB_EMPTY 0x8D
#define BF_SYM_PB_END 0x8E
#define BF_SYM_PB_CLOSE 0x8F
// Batt evolution
#define BF_SYM_BATT_FULL 0x90
#define BF_SYM_BATT_5 0x91
#define BF_SYM_BATT_4 0x92
#define BF_SYM_BATT_3 0x93
#define BF_SYM_BATT_2 0x94
#define BF_SYM_BATT_1 0x95
#define BF_SYM_BATT_EMPTY 0x96
// Batt Icons
#define BF_SYM_MAIN_BATT 0x97
// Voltage and amperage
#define BF_SYM_VOLT 0x06
#define BF_SYM_AMP 0x9A
#define BF_SYM_MAH 0x07
#define BF_SYM_WATT 0x57 // 0x57 is 'W'
// Time
#define BF_SYM_ON_M 0x9B
#define BF_SYM_FLY_M 0x9C
// Speed
#define BF_SYM_SPEED 0x70
#define BF_SYM_KPH 0x9E
#define BF_SYM_MPH 0x9D
#define BF_SYM_MPS 0x9F
#define BF_SYM_FTPS 0x99
// Menu cursor
#define BF_SYM_CURSOR BF_SYM_AH_LEFT
// Stick overlays
#define BF_SYM_STICK_OVERLAY_SPRITE_HIGH 0x08
#define BF_SYM_STICK_OVERLAY_SPRITE_MID 0x09
#define BF_SYM_STICK_OVERLAY_SPRITE_LOW 0x0A
#define BF_SYM_STICK_OVERLAY_CENTER 0x0B
#define BF_SYM_STICK_OVERLAY_VERTICAL 0x16
#define BF_SYM_STICK_OVERLAY_HORIZONTAL 0x17
// GPS degree/minute/second symbols
#define BF_SYM_GPS_DEGREE BF_SYM_STICK_OVERLAY_SPRITE_HIGH // kind of looks like the degree symbol
#define BF_SYM_GPS_MINUTE 0x27 // '
#define BF_SYM_GPS_SECOND 0x22 // "

View file

@ -0,0 +1,687 @@
/*
* This file is part of INAV Project.
*
* 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.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_MSP_DISPLAYPORT
#ifndef DISABLE_MSP_BF_COMPAT
#include "io/displayport_msp_bf_compat.h"
#include "io/bf_osd_symbols.h"
#include "drivers/osd_symbols.h"
uint8_t getBfCharacter(uint8_t ch, uint8_t page)
{
uint16_t ech = ch | (page << 8);
if (ech >= 0x20 && ech <= 0x5F) { // ASCII range
return ch;
}
switch (ech) {
case SYM_RSSI:
return BF_SYM_RSSI;
case SYM_LQ:
return BF_SYM_LINK_QUALITY;
case SYM_LAT:
return BF_SYM_LAT;
case SYM_LON:
return BF_SYM_LON;
case SYM_SAT_L:
return BF_SYM_SAT_L;
case SYM_SAT_R:
return BF_SYM_SAT_R;
case SYM_HOME_NEAR:
return BF_SYM_HOMEFLAG;
case SYM_DEGREES:
return BF_SYM_GPS_DEGREE;
/*
case SYM_HEADING:
return BF_SYM_HEADING;
case SYM_SCALE:
return BF_SYM_SCALE;
case SYM_HDP_L:
return BF_SYM_HDP_L;
case SYM_HDP_R:
return BF_SYM_HDP_R;
*/
case SYM_HOME:
return BF_SYM_HOMEFLAG;
case SYM_2RSS:
return BF_SYM_RSSI;
/*
case SYM_DB:
return BF_SYM_DB
case SYM_DBM:
return BF_SYM_DBM;
case SYM_SNR:
return BF_SYM_SNR;
case SYM_AH_DECORATION_UP:
return BF_SYM_AH_DECORATION_UP;
case SYM_AH_DECORATION_DOWN:
return BF_SYM_AH_DECORATION_DOWN;
case SYM_DIRECTION:
return BF_SYM_DIRECTION;
*/
case SYM_VOLT:
return BF_SYM_VOLT;
case SYM_MAH:
return BF_SYM_MAH;
case SYM_AH_KM:
return BF_SYM_KM;
case SYM_AH_MI:
return BF_SYM_MILES;
/*
case SYM_VTX_POWER:
return BF_SYM_VTX_POWER;
case SYM_AH_NM:
return BF_SYM_AH_NM;
case SYM_MAH_NM_0:
return BF_SYM_MAH_NM_0;
case SYM_MAH_NM_1:
return BF_SYM_MAH_NM_1;
case SYM_MAH_KM_0:
return BF_SYM_MAH_KM_0;
case SYM_MAH_KM_1:
return BF_SYM_MAH_KM_1;
case SYM_MILLIOHM:
return BF_SYM_MILLIOHM;
*/
case SYM_BATT_FULL:
return BF_SYM_BATT_FULL;
case SYM_BATT_5:
return BF_SYM_BATT_5;
case SYM_BATT_4:
return BF_SYM_BATT_4;
case SYM_BATT_3:
return BF_SYM_BATT_3;
case SYM_BATT_2:
return BF_SYM_BATT_2;
case SYM_BATT_1:
return BF_SYM_BATT_1;
case SYM_BATT_EMPTY:
return BF_SYM_BATT_EMPTY;
case SYM_AMP:
return BF_SYM_AMP;
/*
case SYM_WH:
return BF_SYM_WH;
case SYM_WH_KM:
return BF_SYM_WH_KM;
case SYM_WH_MI:
return BF_SYM_WH_MI;
case SYM_WH_NM:
return BF_SYM_WH_NM;
*/
case SYM_WATT:
return BF_SYM_WATT;
/*
case SYM_MW:
return BF_SYM_MW;
case SYM_KILOWATT:
return BF_SYM_KILOWATT;
*/
case SYM_FT:
return BF_SYM_FT;
/*
case SYM_TRIP_DIST:
return BF_SYM_TRIP_DIST;
case SYM_TOTAL:
return BF_SYM_TOTAL;
case SYM_ALT_M:
return BF_SYM_ALT_M;
case SYM_ALT_KM:
return BF_SYM_ALT_KM;
case SYM_ALT_FT:
return BF_SYM_ALT_FT;
case SYM_ALT_KFT:
return BF_SYM_ALT_KFT;
case SYM_DIST_M:
return BF_SYM_DIST_M;
case SYM_DIST_KM:
return BF_SYM_DIST_KM;
case SYM_DIST_FT:
return BF_SYM_DIST_FT;
case SYM_DIST_MI:
return BF_SYM_DIST_MI;
case SYM_DIST_NM:
return BF_SYM_DIST_NM;
*/
case SYM_M:
return BF_SYM_M;
case SYM_KM:
return BF_SYM_KM;
case SYM_MI:
return BF_SYM_MILES;
/*
case SYM_NM:
return BF_SYM_NM;
case SYM_WIND_HORIZONTAL:
return BF_SYM_WIND_HORIZONTAL;
case SYM_WIND_VERTICAL:
return BF_SYM_WIND_VERTICAL;
case SYM_3D_KMH:
return BF_SYM_3D_KMH;
case SYM_3D_MPH:
return BF_SYM_3D_MPH;
case SYM_3D_KT:
return BF_SYM_3D_KT;
case SYM_RPM:
return BF_SYM_RPM;
case SYM_AIR:
return BF_SYM_AIR;
*/
case SYM_FTS:
return BF_SYM_FTPS;
/*
case SYM_100FTM:
return BF_SYM_100FTM;
*/
case SYM_MS:
return BF_SYM_MPS;
case SYM_KMH:
return BF_SYM_KPH;
case SYM_MPH:
return BF_SYM_MPH;
/*
case SYM_KT:
return BF_SYM_KT
case SYM_MAH_MI_0:
return BF_SYM_MAH_MI_0;
case SYM_MAH_MI_1:
return BF_SYM_MAH_MI_1;
*/
case SYM_THR:
return BF_SYM_THR;
/*
case SYM_TEMP_F:
return BF_SYM_TEMP_F;
case SYM_TEMP_C:
return BF_SYM_TEMP_C;
*/
case SYM_BLANK:
return BF_SYM_BLANK;
/*
case SYM_ON_H:
return BF_SYM_ON_H;
case SYM_FLY_H:
return BF_SYM_FLY_H;
*/
case SYM_ON_M:
return BF_SYM_ON_M;
case SYM_FLY_M:
return BF_SYM_FLY_M;
/*
case SYM_GLIDESLOPE:
return BF_SYM_GLIDESLOPE;
case SYM_WAYPOINT:
return BF_SYM_WAYPOINT;
case SYM_CLOCK:
return BF_SYM_CLOCK;
case SYM_ZERO_HALF_TRAILING_DOT:
return BF_SYM_ZERO_HALF_TRAILING_DOT;
case SYM_ZERO_HALF_LEADING_DOT:
return BF_SYM_ZERO_HALF_LEADING_DOT;
case SYM_AUTO_THR0:
return BF_SYM_AUTO_THR0;
case SYM_AUTO_THR1:
return BF_SYM_AUTO_THR1;
case SYM_ROLL_LEFT:
return BF_SYM_ROLL_LEFT;
case SYM_ROLL_LEVEL:
return BF_SYM_ROLL_LEVEL;
case SYM_ROLL_RIGHT:
return BF_SYM_ROLL_RIGHT;
case SYM_PITCH_UP:
return BF_SYM_PITCH_UP;
case SYM_PITCH_DOWN:
return BF_SYM_PITCH_DOWN;
case SYM_GFORCE:
return BF_SYM_GFORCE;
case SYM_GFORCE_X:
return BF_SYM_GFORCE_X;
case SYM_GFORCE_Y:
return BF_SYM_GFORCE_Y;
case SYM_GFORCE_Z:
return BF_SYM_GFORCE_Z;
case SYM_BARO_TEMP:
return BF_SYM_BARO_TEMP;
case SYM_IMU_TEMP:
return BF_SYM_IMU_TEMP;
case SYM_TEMP:
return BF_SYM_TEMP;
case SYM_TEMP_SENSOR_FIRST:
return BF_SYM_TEMP_SENSOR_FIRST;
case SYM_ESC_TEMP:
return BF_SYM_ESC_TEMP;
case SYM_TEMP_SENSOR_LAST:
return BF_SYM_TEMP_SENSOR_LAST;
case TEMP_SENSOR_SYM_COUNT:
return BF_TEMP_SENSOR_SYM_COUNT;
*/
case SYM_HEADING_N:
return BF_SYM_HEADING_N;
case SYM_HEADING_S:
return BF_SYM_HEADING_S;
case SYM_HEADING_E:
return BF_SYM_HEADING_E;
case SYM_HEADING_W:
return BF_SYM_HEADING_W;
case SYM_HEADING_DIVIDED_LINE:
return BF_SYM_HEADING_DIVIDED_LINE;
case SYM_HEADING_LINE:
return BF_SYM_HEADING_LINE;
/*
case SYM_MAX:
return BF_SYM_MAX;
case SYM_PROFILE:
return BF_SYM_PROFILE;
case SYM_SWITCH_INDICATOR_LOW:
return BF_SYM_SWITCH_INDICATOR_LOW;
case SYM_SWITCH_INDICATOR_MID:
return BF_SYM_SWITCH_INDICATOR_MID;
case SYM_SWITCH_INDICATOR_HIGH:
return BF_SYM_SWITCH_INDICATOR_HIGH;
case SYM_AH:
return BF_SYM_AH;
case SYM_GLIDE_DIST:
return BF_SYM_GLIDE_DIST;
case SYM_GLIDE_MINS:
return BF_SYM_GLIDE_MINS;
case SYM_AH_V_FT_0:
return BF_SYM_AH_V_FT_0;
case SYM_AH_V_FT_1:
return BF_SYM_AH_V_FT_1;
case SYM_AH_V_M_0:
return BF_SYM_AH_V_M_0;
case SYM_AH_V_M_1:
return BF_SYM_AH_V_M_1;
case SYM_FLIGHT_MINS_REMAINING:
return BF_SYM_FLIGHT_MINS_REMAINING;
case SYM_FLIGHT_HOURS_REMAINING:
return BF_SYM_FLIGHT_HOURS_REMAINING;
case SYM_GROUND_COURSE:
return BF_SYM_GROUND_COURSE;
case SYM_CROSS_TRACK_ERROR:
return BF_SYM_CROSS_TRACK_ERROR;
case SYM_LOGO_START:
return BF_SYM_LOGO_START;
case SYM_LOGO_WIDTH:
return BF_SYM_LOGO_WIDTH;
case SYM_LOGO_HEIGHT:
return BF_SYM_LOGO_HEIGHT;
*/
case SYM_AH_LEFT:
return BF_SYM_AH_LEFT;
case SYM_AH_RIGHT:
return BF_SYM_AH_RIGHT;
/*
case SYM_AH_DECORATION_MIN:
return BF_SYM_AH_DECORATION_MIN;
*/
case SYM_AH_DECORATION:
return BF_SYM_AH_DECORATION;
/*
case SYM_AH_DECORATION_MAX:
return BF_SYM_AH_DECORATION_MAX;
case SYM_AH_DECORATION_COUNT:
return BF_SYM_AH_DECORATION_COUNT;
*/
case SYM_AH_CH_LEFT:
case SYM_AH_CH_TYPE3:
case SYM_AH_CH_TYPE4:
case SYM_AH_CH_TYPE5:
case SYM_AH_CH_TYPE6:
case SYM_AH_CH_TYPE7:
case SYM_AH_CH_TYPE8:
case SYM_AH_CH_AIRCRAFT1:
return BF_SYM_AH_CENTER_LINE;
case SYM_AH_CH_RIGHT:
case (SYM_AH_CH_TYPE3+2):
case (SYM_AH_CH_TYPE4+2):
case (SYM_AH_CH_TYPE5+2):
case (SYM_AH_CH_TYPE6+2):
case (SYM_AH_CH_TYPE7+2):
case (SYM_AH_CH_TYPE8+2):
case SYM_AH_CH_AIRCRAFT3:
return BF_SYM_AH_CENTER_LINE_RIGHT;
case SYM_AH_CH_AIRCRAFT0:
case SYM_AH_CH_AIRCRAFT4:
return ' ';
case SYM_ARROW_UP:
return BF_SYM_ARROW_NORTH;
case SYM_ARROW_2:
return BF_SYM_ARROW_8;
case SYM_ARROW_3:
return BF_SYM_ARROW_7;
case SYM_ARROW_4:
return BF_SYM_ARROW_6;
case SYM_ARROW_RIGHT:
return BF_SYM_ARROW_EAST;
case SYM_ARROW_6:
return BF_SYM_ARROW_4;
case SYM_ARROW_7:
return BF_SYM_ARROW_3;
case SYM_ARROW_8:
return BF_SYM_ARROW_2;
case SYM_ARROW_DOWN:
return BF_SYM_ARROW_SOUTH;
case SYM_ARROW_10:
return BF_SYM_ARROW_16;
case SYM_ARROW_11:
return BF_SYM_ARROW_15;
case SYM_ARROW_12:
return BF_SYM_ARROW_14;
case SYM_ARROW_LEFT:
return BF_SYM_ARROW_WEST;
case SYM_ARROW_14:
return BF_SYM_ARROW_12;
case SYM_ARROW_15:
return BF_SYM_ARROW_11;
case SYM_ARROW_16:
return BF_SYM_ARROW_10;
case SYM_AH_H_START:
return BF_SYM_AH_BAR9_0;
case (SYM_AH_H_START+1):
return BF_SYM_AH_BAR9_1;
case (SYM_AH_H_START+2):
return BF_SYM_AH_BAR9_2;
case (SYM_AH_H_START+3):
return BF_SYM_AH_BAR9_3;
case (SYM_AH_H_START+4):
return BF_SYM_AH_BAR9_4;
case (SYM_AH_H_START+5):
return BF_SYM_AH_BAR9_5;
case (SYM_AH_H_START+6):
return BF_SYM_AH_BAR9_6;
case (SYM_AH_H_START+7):
return BF_SYM_AH_BAR9_7;
case (SYM_AH_H_START+8):
return BF_SYM_AH_BAR9_8;
/*
case SYM_AH_V_START:
return BF_SYM_AH_V_START;
case SYM_VARIO_UP_2A:
return BF_SYM_VARIO_UP_2A;
case SYM_VARIO_UP_1A:
return BF_SYM_VARIO_UP_1A;
case SYM_VARIO_DOWN_1A:
return BF_SYM_VARIO_DOWN_1A;
case SYM_VARIO_DOWN_2A:
return BF_SYM_VARIO_DOWN_2A;
*/
case SYM_ALT:
return BF_SYM_ALTITUDE;
/*
case SYM_HUD_SIGNAL_0:
return BF_SYM_HUD_SIGNAL_0;
case SYM_HUD_SIGNAL_1:
return BF_SYM_HUD_SIGNAL_1;
case SYM_HUD_SIGNAL_2:
return BF_SYM_HUD_SIGNAL_2;
case SYM_HUD_SIGNAL_3:
return BF_SYM_HUD_SIGNAL_3;
case SYM_HUD_SIGNAL_4:
return BF_SYM_HUD_SIGNAL_4;
case SYM_HOME_DIST:
return BF_SYM_HOME_DIST;
*/
case SYM_AH_CH_CENTER:
case (SYM_AH_CH_TYPE3+1):
case (SYM_AH_CH_TYPE4+1):
case (SYM_AH_CH_TYPE5+1):
case (SYM_AH_CH_TYPE6+1):
case (SYM_AH_CH_TYPE7+1):
case (SYM_AH_CH_TYPE8+1):
case SYM_AH_CH_AIRCRAFT2:
return BF_SYM_AH_CENTER;
/*
case SYM_FLIGHT_DIST_REMAINING:
return BF_SYM_FLIGHT_DIST_REMAINING;
case SYM_AH_CH_TYPE3:
return BF_SYM_AH_CH_TYPE3;
case SYM_AH_CH_TYPE4:
return BF_SYM_AH_CH_TYPE4;
case SYM_AH_CH_TYPE5:
return BF_SYM_AH_CH_TYPE5;
case SYM_AH_CH_TYPE6:
return BF_SYM_AH_CH_TYPE6;
case SYM_AH_CH_TYPE7:
return BF_SYM_AH_CH_TYPE7;
case SYM_AH_CH_TYPE8:
return BF_SYM_AH_CH_TYPE8;
case SYM_AH_CH_AIRCRAFT0:
return BF_SYM_AH_CH_AIRCRAFT0;
case SYM_AH_CH_AIRCRAFT1:
return BF_SYM_AH_CH_AIRCRAFT1;
case SYM_AH_CH_AIRCRAFT2:
return BF_SYM_AH_CH_AIRCRAFT2;
case SYM_AH_CH_AIRCRAFT3:
return BF_SYM_AH_CH_AIRCRAFT3;
case SYM_AH_CH_AIRCRAFT4:
return BF_SYM_AH_CH_AIRCRAFT4;
case SYM_HUD_ARROWS_L1:
return BF_SYM_HUD_ARROWS_L1;
case SYM_HUD_ARROWS_L2:
return BF_SYM_HUD_ARROWS_L2;
case SYM_HUD_ARROWS_L3:
return BF_SYM_HUD_ARROWS_L3;
case SYM_HUD_ARROWS_R1:
return BF_SYM_HUD_ARROWS_R1;
case SYM_HUD_ARROWS_R2:
return BF_SYM_HUD_ARROWS_R2;
case SYM_HUD_ARROWS_R3:
return BF_SYM_HUD_ARROWS_R3;
case SYM_HUD_ARROWS_U1:
return BF_SYM_HUD_ARROWS_U1;
case SYM_HUD_ARROWS_U2:
return BF_SYM_HUD_ARROWS_U2;
case SYM_HUD_ARROWS_U3:
return BF_SYM_HUD_ARROWS_U3;
case SYM_HUD_ARROWS_D1:
return BF_SYM_HUD_ARROWS_D1;
case SYM_HUD_ARROWS_D2:
return BF_SYM_HUD_ARROWS_D2;
case SYM_HUD_ARROWS_D3:
return BF_SYM_HUD_ARROWS_D3;
*/
default:
break;
}
return '?'; // Missing/not mapped character
}
#endif
#endif

View file

@ -0,0 +1,36 @@
/*
* This file is part of INAV Project.
*
* 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.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
#include "platform.h"
#ifdef USE_MSP_DISPLAYPORT
#ifndef DISABLE_MSP_BF_COMPAT
#include "osd.h"
uint8_t getBfCharacter(uint8_t ch, uint8_t page);
#define isBfCompatibleVideoSystem(osdConfigPtr) (osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT)
#else
#define getBfCharacter(x, page) (x)
#define isBfCompatibleVideoSystem(osdConfigPtr) (false)
#endif
#endif

View file

@ -52,8 +52,12 @@ FILE_COMPILE_FOR_SPEED
#include "displayport_msp_osd.h"
#include "displayport_msp_bf_compat.h"
#define FONT_VERSION 3
#define MSP_HEARTBEAT 0
#define MSP_RELEASE 1
#define MSP_CLEAR_SCREEN 2
#define MSP_WRITE_STRING 3
#define MSP_DRAW_SCREEN 4
@ -273,7 +277,7 @@ static int drawScreen(displayPort_t *displayPort) // 250Hz
uint8_t len = 4;
do {
bitArrayClr(dirty, pos);
subcmd[len++] = screen[pos++];
subcmd[len++] = (osdVideoSystem == VIDEO_SYSTEM_BFCOMPAT) ? getBfCharacter(screen[pos++], page): screen[pos++];
if (bitArrayGet(dirty, pos)) {
next = pos;
@ -282,7 +286,7 @@ static int drawScreen(displayPort_t *displayPort) // 250Hz
subcmd[1] = row;
subcmd[2] = col;
subcmd[3] = page;
subcmd[3] = (osdVideoSystem == VIDEO_SYSTEM_BFCOMPAT) ? 0 : page;
output(displayPort, MSP_DISPLAYPORT, subcmd, len);
updateCount++;
next = BITARRAY_FIND_FIRST_SET(dirty, pos);
@ -348,22 +352,21 @@ static bool isReady(displayPort_t *displayPort)
return vtxActive;
}
static int grab(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}
static int heartbeat(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
uint8_t subcmd[] = { MSP_HEARTBEAT };
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
static int grab(displayPort_t *displayPort)
{
return heartbeat(displayPort);
}
static int release(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
uint8_t subcmd[] = { MSP_RELEASE };
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
static const displayPortVTable_t mspOsdVTable = {
@ -415,6 +418,7 @@ displayPort_t* mspOsdDisplayPortInit(const videoSystem_e videoSystem)
if (mspOsdSerialInit()) {
switch(videoSystem) {
case VIDEO_SYSTEM_AUTO:
case VIDEO_SYSTEM_BFCOMPAT:
case VIDEO_SYSTEM_PAL:
currentOsdMode = SD_3016;
screenRows = PAL_ROWS;

View file

@ -69,6 +69,7 @@ FILE_COMPILE_FOR_SPEED
#include "io/osd.h"
#include "io/osd_common.h"
#include "io/osd_hud.h"
#include "io/displayport_msp_bf_compat.h"
#include "io/vtx.h"
#include "io/vtx_string.h"
@ -241,6 +242,7 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
int decimals = maxDecimals;
bool negative = false;
bool scaled = false;
bool explicitDecimal = isBfCompatibleVideoSystem(osdConfig());
buff[length] = '\0';
@ -256,6 +258,9 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
int digits = digitCount(integerPart);
int remaining = length - digits;
if (explicitDecimal) {
remaining--;
}
if (remaining < 0 && scale > 0) {
// Reduce by scale
@ -266,6 +271,9 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
millis = ((centivalue % (100 * scale)) * 10) / scale;
digits = digitCount(integerPart);
remaining = length - digits;
if (explicitDecimal) {
remaining--;
}
}
// 3 decimals at most
@ -289,8 +297,14 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
// Now write the digits.
ui2a(integerPart, 10, 0, ptr);
ptr += digits;
if (decimals > 0) {
*(ptr-1) += SYM_ZERO_HALF_TRAILING_DOT - '0';
if (explicitDecimal) {
*ptr = '.';
ptr++;
} else {
*(ptr - 1) += SYM_ZERO_HALF_TRAILING_DOT - '0';
}
dec = ptr;
int factor = 3; // we're getting the decimal part in millis first
while (decimals < factor) {
@ -304,8 +318,10 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
ptr++;
}
ui2a(millis, 10, 0, ptr);
if (!explicitDecimal) {
*dec += SYM_ZERO_HALF_LEADING_DOT - '0';
}
}
return scaled;
}
@ -715,10 +731,15 @@ static void osdFormatCoordinate(char *buff, char sym, int32_t val)
// We can show up to 7 digits in decimalPart.
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits);
int decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart);
int decimalDigits;
if (!isBfCompatibleVideoSystem(osdConfig())) {
decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart);
// Embbed the decimal separator
buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0';
} else {
decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart);
}
// Fill up to coordinateLength with zeros
int total = 1 + integerDigits + decimalDigits;
while(total < coordinateLength) {
@ -1389,7 +1410,7 @@ static void osdFormatPidControllerOutput(char *buff, const char *label, const pi
static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_t voltage, uint8_t digits, uint8_t decimals)
{
char buff[6];
char buff[7];
textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE;
osdFormatBatteryChargeSymbol(buff);
@ -1398,7 +1419,7 @@ static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
elemAttr = TEXT_ATTRIBUTES_NONE;
digits = MIN(digits, 4);
digits = MIN(digits, 5);
osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits);
buff[digits] = SYM_VOLT;
buff[digits+1] = '\0';
@ -1574,11 +1595,11 @@ static bool osdDrawSingleElement(uint8_t item)
}
case OSD_MAIN_BATT_VOLTAGE:
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), 2 + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals);
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 3 : 2) + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals);
return true;
case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE:
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), 2 + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals);
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 3 : 2) + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals);
return true;
case OSD_CURRENT_DRAW:
@ -2687,13 +2708,13 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_MAIN_BATT_CELL_VOLTAGE:
{
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), 3, 2);
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 4 : 3), 2);
return true;
}
case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE:
{
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), 3, 2);
osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 4 : 3), 2);
return true;
}
@ -2982,7 +3003,7 @@ static bool osdDrawSingleElement(uint8_t item)
if (h < 0) {
h += 360;
}
if(h >= 180)
if (h >= 180)
h = h - 180;
else
h = h + 180;

View file

@ -256,9 +256,9 @@ static void clearJumpCounters(void);
static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint);
static void calculateAndSetActiveWaypointToLocalPosition(const fpVector3_t * pos);
void calculateInitialHoldPosition(fpVector3_t * pos);
void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t yaw, int32_t distance);
void calculateNewCruiseTarget(fpVector3_t * origin, int32_t yaw, int32_t distance);
static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * waypointYaw);
void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t bearing, int32_t distance);
void calculateNewCruiseTarget(fpVector3_t * origin, int32_t course, int32_t distance);
static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * waypointBearing);
bool isWaypointAltitudeReached(void);
static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint_t * waypoint, geoAltitudeConversionMode_e altConv);
static navigationFSMEvent_t nextForNonGeoStates(void);
@ -1072,9 +1072,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_INITIALIZE(
resetPositionController();
}
posControl.cruise.yaw = posControl.actualState.yaw; // Store the yaw to follow
posControl.cruise.previousYaw = posControl.cruise.yaw;
posControl.cruise.lastYawAdjustmentTime = 0;
posControl.cruise.course = posControl.actualState.cog; // Store the course to follow
posControl.cruise.previousCourse = posControl.cruise.course;
posControl.cruise.lastCourseAdjustmentTime = 0;
return NAV_FSM_EVENT_SUCCESS; // Go to CRUISE_XD_IN_PROGRESS state
}
@ -1096,31 +1096,31 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS
// User is yawing. We record the desidered yaw and we change the desidered target in the meanwhile
if (posControl.flags.isAdjustingHeading) {
timeMs_t timeDifference = currentTimeMs - posControl.cruise.lastYawAdjustmentTime;
timeMs_t timeDifference = currentTimeMs - posControl.cruise.lastCourseAdjustmentTime;
if (timeDifference > 100) timeDifference = 0; // if adjustment was called long time ago, reset the time difference.
float rateTarget = scaleRangef((float)rcCommand[YAW], -500.0f, 500.0f, -DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate), DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate));
float centidegsPerIteration = rateTarget * timeDifference * 0.001f;
posControl.cruise.yaw = wrap_36000(posControl.cruise.yaw - centidegsPerIteration);
DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.yaw));
posControl.cruise.lastYawAdjustmentTime = currentTimeMs;
posControl.cruise.course = wrap_36000(posControl.cruise.course - centidegsPerIteration);
DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.course));
posControl.cruise.lastCourseAdjustmentTime = currentTimeMs;
}
if (currentTimeMs - posControl.cruise.lastYawAdjustmentTime > 4000)
posControl.cruise.previousYaw = posControl.cruise.yaw;
if (currentTimeMs - posControl.cruise.lastCourseAdjustmentTime > 4000)
posControl.cruise.previousCourse = posControl.cruise.course;
uint32_t distance = gpsSol.groundSpeed * 60; // next WP to be reached in 60s [cm]
if ((previousState == NAV_STATE_COURSE_HOLD_INITIALIZE) || (previousState == NAV_STATE_COURSE_HOLD_ADJUSTING)
|| (previousState == NAV_STATE_CRUISE_INITIALIZE) || (previousState == NAV_STATE_CRUISE_ADJUSTING)
|| posControl.flags.isAdjustingHeading) {
calculateFarAwayTarget(&posControl.cruise.targetPos, posControl.cruise.yaw, distance);
calculateFarAwayTarget(&posControl.cruise.targetPos, posControl.cruise.course, distance);
DEBUG_SET(DEBUG_CRUISE, 2, 1);
} else if (calculateDistanceToDestination(&posControl.cruise.targetPos) <= (navConfig()->fw.loiter_radius * 1.10f)) { //10% margin
calculateNewCruiseTarget(&posControl.cruise.targetPos, posControl.cruise.yaw, distance);
calculateNewCruiseTarget(&posControl.cruise.targetPos, posControl.cruise.course, distance);
DEBUG_SET(DEBUG_CRUISE, 2, 2);
}
setDesiredPosition(&posControl.cruise.targetPos, posControl.cruise.yaw, NAV_POS_UPDATE_XY);
setDesiredPosition(&posControl.cruise.targetPos, posControl.cruise.course, NAV_POS_UPDATE_XY);
return NAV_FSM_EVENT_NONE;
}
@ -1132,8 +1132,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_ADJUSTING(n
// User is rolling, changing manually direction. Wait until it is done and then restore CRUISE
if (posControl.flags.isAdjustingPosition) {
posControl.cruise.yaw = posControl.actualState.yaw; //store current heading
posControl.cruise.lastYawAdjustmentTime = millis();
posControl.cruise.course = posControl.actualState.cog; //store current course
posControl.cruise.lastCourseAdjustmentTime = millis();
return NAV_FSM_EVENT_NONE; // reprocess the state
}
@ -1222,7 +1222,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
// Spiral climb centered at xy of RTH activation
calculateInitialHoldPosition(&targetHoldPos);
} else {
calculateFarAwayTarget(&targetHoldPos, posControl.actualState.yaw, 100000.0f); // 1km away Linear climb
calculateFarAwayTarget(&targetHoldPos, posControl.actualState.cog, 100000.0f); // 1km away Linear climb
}
} else {
// Multicopter, hover and climb
@ -1341,7 +1341,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_TRACKBACK(navigatio
return NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_INITIALIZE; // procede to home after final trackback point
}
if (isWaypointReached(&posControl.activeWaypoint.pos, &posControl.activeWaypoint.yaw)) {
if (isWaypointReached(&posControl.activeWaypoint.pos, &posControl.activeWaypoint.bearing)) {
posControl.activeRthTBPointIndex--;
if (posControl.rthTBWrapAroundCounter > -1 && posControl.activeRthTBPointIndex < 0) {
@ -1377,7 +1377,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio
if (isWaypointReached(tmpHomePos, 0)) {
// Successfully reached position target - update XYZ-position
setDesiredPosition(tmpHomePos, posControl.rthState.homePosition.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
setDesiredPosition(tmpHomePos, posControl.rthState.homePosition.heading, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_RTH_HOVER_PRIOR_TO_LANDING
} else {
setDesiredPosition(tmpHomePos, 0, NAV_POS_UPDATE_Z | NAV_POS_UPDATE_XY);
@ -1408,13 +1408,13 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HOVER_PRIOR_TO_LAND
// If position ok OR within valid timeout - continue
// Wait until target heading is reached for MR (with 15 deg margin for error), or continue for Fixed Wing
if ((ABS(wrap_18000(posControl.rthState.homePosition.yaw - posControl.actualState.yaw)) < DEGREES_TO_CENTIDEGREES(15)) || STATE(FIXED_WING_LEGACY)) {
if ((ABS(wrap_18000(posControl.rthState.homePosition.heading - posControl.actualState.yaw)) < DEGREES_TO_CENTIDEGREES(15)) || STATE(FIXED_WING_LEGACY)) {
resetLandingDetector(); // force reset landing detector just in case
updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME; // success = land
} else {
fpVector3_t * tmpHomePos = rthGetHomeTargetPosition(RTH_HOME_ENROUTE_FINAL);
setDesiredPosition(tmpHomePos, posControl.rthState.homePosition.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
setDesiredPosition(tmpHomePos, posControl.rthState.homePosition.heading, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
return NAV_FSM_EVENT_NONE;
}
}
@ -1629,7 +1629,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na
case NAV_WP_ACTION_HOLD_TIME:
case NAV_WP_ACTION_WAYPOINT:
case NAV_WP_ACTION_LAND:
if (isWaypointReached(&posControl.activeWaypoint.pos, &posControl.activeWaypoint.yaw)) {
if (isWaypointReached(&posControl.activeWaypoint.pos, &posControl.activeWaypoint.bearing)) {
return NAV_FSM_EVENT_SUCCESS; // will switch to NAV_STATE_WAYPOINT_REACHED
}
else {
@ -2140,19 +2140,14 @@ void updateActualHeading(bool headingValid, int32_t newHeading, int32_t newGroun
// the offset from the fake to the actual yaw and apply the same rotation
// to the home point.
int32_t fakeToRealYawOffset = newHeading - posControl.actualState.yaw;
posControl.rthState.homePosition.heading += fakeToRealYawOffset;
posControl.rthState.homePosition.heading = wrap_36000(posControl.rthState.homePosition.heading);
posControl.rthState.homePosition.yaw += fakeToRealYawOffset;
if (posControl.rthState.homePosition.yaw < 0) {
posControl.rthState.homePosition.yaw += DEGREES_TO_CENTIDEGREES(360);
}
if (posControl.rthState.homePosition.yaw >= DEGREES_TO_CENTIDEGREES(360)) {
posControl.rthState.homePosition.yaw -= DEGREES_TO_CENTIDEGREES(360);
}
posControl.rthState.homeFlags |= NAV_HOME_VALID_HEADING;
}
/* Use course over ground for fixed wing nav "heading" when valid - TODO use heading and cog as specifically required for FW and MR */
posControl.actualState.yaw = newHeading;
posControl.actualState.cog = newGroundCourse; // currently only used for OSD display
posControl.actualState.cog = newGroundCourse;
posControl.flags.estHeadingStatus = newEstHeading;
/* Precompute sin/cos of yaw angle */
@ -2207,7 +2202,7 @@ int32_t calculateBearingBetweenLocalPositions(const fpVector3_t * startPos, cons
return calculateBearingFromDelta(deltaX, deltaY);
}
bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3_t * destinationPos)
bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3_t * destinationPos) // NOT USED ANYWHERE
{
if (posControl.flags.estPosStatus == EST_NONE ||
posControl.flags.estHeadingStatus == EST_NONE) {
@ -2254,9 +2249,9 @@ static bool getLocalPosNextWaypoint(fpVector3_t * nextWpPos)
/*-----------------------------------------------------------
* Check if waypoint is/was reached.
* waypointYaw stores initial bearing to waypoint
* waypointBearing stores initial bearing to waypoint
*-----------------------------------------------------------*/
static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * waypointYaw)
static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * waypointBearing)
{
posControl.wpDistance = calculateDistanceToDestination(waypointPos);
@ -2275,7 +2270,7 @@ static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * w
// Check if waypoint was missed based on bearing to WP exceeding 100 degrees relative to waypoint Yaw
// Same method for turn smoothing option but relative bearing set at 60 degrees
uint16_t relativeBearing = posControl.flags.wpTurnSmoothingActive ? 6000 : 10000;
if (ABS(wrap_18000(calculateBearingToDestination(waypointPos) - *waypointYaw)) > relativeBearing) {
if (ABS(wrap_18000(calculateBearingToDestination(waypointPos) - *waypointBearing)) > relativeBearing) {
return true;
}
}
@ -2409,7 +2404,7 @@ bool validateRTHSanityChecker(void)
/*-----------------------------------------------------------
* Reset home position to current position
*-----------------------------------------------------------*/
void setHomePosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlags_t useMask, navigationHomeFlags_t homeFlags)
void setHomePosition(const fpVector3_t * pos, int32_t heading, navSetWaypointFlags_t useMask, navigationHomeFlags_t homeFlags)
{
// XY-position
if ((useMask & NAV_POS_UPDATE_XY) != 0) {
@ -2435,7 +2430,7 @@ void setHomePosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlags_t
// Heading
if ((useMask & NAV_POS_UPDATE_HEADING) != 0) {
// Heading
posControl.rthState.homePosition.yaw = yaw;
posControl.rthState.homePosition.heading = heading;
if (homeFlags & NAV_HOME_VALID_HEADING) {
posControl.rthState.homeFlags |= NAV_HOME_VALID_HEADING;
} else {
@ -2686,7 +2681,7 @@ static bool rthAltControlStickOverrideCheck(unsigned axis)
if (posControl.activeRthTBPointIndex < 0) {
saveTrackpoint = posControl.homeDistance > METERS_TO_CENTIMETERS(50);
previousTBCourse = CENTIDEGREES_TO_DEGREES(posControl.actualState.yaw);
previousTBCourse = CENTIDEGREES_TO_DEGREES(posControl.actualState.cog);
previousTBTripDist = posControl.totalTripDistance;
} else {
// Minimum distance increment between course change track points when GPS course valid - set to 10m
@ -2817,17 +2812,17 @@ void setDesiredPosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlag
}
}
void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t yaw, int32_t distance)
void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t bearing, int32_t distance)
{
farAwayPos->x = navGetCurrentActualPositionAndVelocity()->pos.x + distance * cos_approx(CENTIDEGREES_TO_RADIANS(yaw));
farAwayPos->y = navGetCurrentActualPositionAndVelocity()->pos.y + distance * sin_approx(CENTIDEGREES_TO_RADIANS(yaw));
farAwayPos->x = navGetCurrentActualPositionAndVelocity()->pos.x + distance * cos_approx(CENTIDEGREES_TO_RADIANS(bearing));
farAwayPos->y = navGetCurrentActualPositionAndVelocity()->pos.y + distance * sin_approx(CENTIDEGREES_TO_RADIANS(bearing));
farAwayPos->z = navGetCurrentActualPositionAndVelocity()->pos.z;
}
void calculateNewCruiseTarget(fpVector3_t * origin, int32_t yaw, int32_t distance)
void calculateNewCruiseTarget(fpVector3_t * origin, int32_t course, int32_t distance)
{
origin->x = origin->x + distance * cos_approx(CENTIDEGREES_TO_RADIANS(yaw));
origin->y = origin->y + distance * sin_approx(CENTIDEGREES_TO_RADIANS(yaw));
origin->x = origin->x + distance * cos_approx(CENTIDEGREES_TO_RADIANS(course));
origin->y = origin->y + distance * sin_approx(CENTIDEGREES_TO_RADIANS(course));
origin->z = origin->z;
}
@ -3397,18 +3392,18 @@ static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint
static void calculateAndSetActiveWaypointToLocalPosition(const fpVector3_t * pos)
{
// Calculate bearing towards waypoint and store it in waypoint yaw parameter (this will further be used to detect missed waypoints)
// Calculate bearing towards waypoint and store it in waypoint bearing parameter (this will further be used to detect missed waypoints)
if (isWaypointNavTrackingActive() && !(posControl.activeWaypoint.pos.x == pos->x && posControl.activeWaypoint.pos.y == pos->y)) {
posControl.activeWaypoint.yaw = calculateBearingBetweenLocalPositions(&posControl.activeWaypoint.pos, pos);
posControl.activeWaypoint.bearing = calculateBearingBetweenLocalPositions(&posControl.activeWaypoint.pos, pos);
} else {
posControl.activeWaypoint.yaw = calculateBearingToDestination(pos);
posControl.activeWaypoint.bearing = calculateBearingToDestination(pos);
}
posControl.activeWaypoint.nextTurnAngle = -1; // no turn angle set (-1), will be set by WP mode as required
posControl.activeWaypoint.pos = *pos;
// Set desired position to next waypoint (XYZ-controller)
setDesiredPosition(&posControl.activeWaypoint.pos, posControl.activeWaypoint.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
setDesiredPosition(&posControl.activeWaypoint.pos, posControl.activeWaypoint.bearing, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
}
geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e datumFlag)
@ -3426,7 +3421,7 @@ static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint)
fpVector3_t posNextWp;
if (getLocalPosNextWaypoint(&posNextWp)) {
int32_t bearingToNextWp = calculateBearingBetweenLocalPositions(&posControl.activeWaypoint.pos, &posNextWp);
posControl.activeWaypoint.nextTurnAngle = wrap_18000(bearingToNextWp - posControl.activeWaypoint.yaw);
posControl.activeWaypoint.nextTurnAngle = wrap_18000(bearingToNextWp - posControl.activeWaypoint.bearing);
}
}
}
@ -3638,8 +3633,9 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
const bool canActivatePosHold = canActivatePosHoldMode();
const bool canActivateNavigation = canActivateNavigationModes();
const bool isExecutingRTH = navGetStateFlags(posControl.navState) & NAV_AUTO_RTH;
#ifdef USE_SAFE_HOME
checkSafeHomeState(isExecutingRTH || posControl.flags.forcedRTHActivated);
#endif
// deactivate rth trackback if RTH not active
if (posControl.flags.rthTrackbackActive) {
posControl.flags.rthTrackbackActive = isExecutingRTH;
@ -3864,7 +3860,6 @@ bool navigationPositionEstimateIsHealthy(void)
navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass)
{
const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD)) || (STATE(FIXED_WING_LEGACY) && (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCRUISE)));
const bool navLaunchComboModesEnabled = isNavLaunchEnabled() && (IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCRUISE));
if (usedBypass) {
*usedBypass = false;
@ -3883,7 +3878,7 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass)
}
// Don't allow arming if any of NAV modes is active
if (!ARMING_FLAG(ARMED) && navBoxModesEnabled && !navLaunchComboModesEnabled) {
if (!ARMING_FLAG(ARMED) && navBoxModesEnabled) {
return NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE;
}
@ -4228,7 +4223,9 @@ void activateForcedRTH(void)
{
abortFixedWingLaunch();
posControl.flags.forcedRTHActivated = true;
#ifdef USE_SAFE_HOME
checkSafeHomeState(true);
#endif
navProcessFSMEvents(selectNavEventFromBoxModeInput());
}
@ -4237,7 +4234,9 @@ void abortForcedRTH(void)
// Disable failsafe RTH and make sure we back out of navigation mode to IDLE
// If any navigation mode was active prior to RTH it will be re-enabled with next RX update
posControl.flags.forcedRTHActivated = false;
#ifdef USE_SAFE_HOME
checkSafeHomeState(false);
#endif
navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE);
}
@ -4350,7 +4349,7 @@ bool abortLaunchAllowed(void)
int32_t navigationGetHomeHeading(void)
{
return posControl.rthState.homePosition.yaw;
return posControl.rthState.homePosition.heading;
}
// returns m/s
@ -4373,5 +4372,5 @@ bool isAdjustingHeading(void) {
}
int32_t getCruiseHeadingAdjustment(void) {
return wrap_18000(posControl.cruise.yaw - posControl.cruise.previousYaw);
return wrap_18000(posControl.cruise.course - posControl.cruise.previousCourse);
}

View file

@ -397,11 +397,12 @@ extern radar_pois_t radar_pois[RADAR_MAX_POIS];
typedef struct {
fpVector3_t pos;
int32_t yaw; // centidegrees
int32_t heading; // centidegrees
int32_t bearing; // centidegrees
int32_t nextTurnAngle; // centidegrees
} navWaypointPosition_t;
typedef struct navDestinationPath_s {
typedef struct navDestinationPath_s { // NOT USED
uint32_t distance; // meters * 100
int32_t bearing; // deg * 100
} navDestinationPath_t;
@ -572,7 +573,7 @@ float geoCalculateMagDeclination(const gpsLocation_t * llh); // degrees units
geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e datumFlag);
/* Distance/bearing calculation */
bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3_t * destinationPos);
bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3_t * destinationPos); // NOT USED
uint32_t distanceToFirstWP(void);
/* Failsafe-forced RTH mode */

View file

@ -305,7 +305,7 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod)
// velXY provides additional turn initiation distance based on an assumed 1 second delayed turn response time
if (posControl.wpDistance < (posControl.actualState.velXY + navLoiterRadius * turnStartFactor)) {
if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_ON) {
int32_t loiterCenterBearing = wrap_36000(((wrap_18000(posControl.activeWaypoint.nextTurnAngle - 18000)) / 2) + posControl.activeWaypoint.yaw + 18000);
int32_t loiterCenterBearing = wrap_36000(((wrap_18000(posControl.activeWaypoint.nextTurnAngle - 18000)) / 2) + posControl.activeWaypoint.bearing + 18000);
loiterCenterPos.x = posControl.activeWaypoint.pos.x + navLoiterRadius * cos_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing));
loiterCenterPos.y = posControl.activeWaypoint.pos.y + navLoiterRadius * sin_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing));
@ -398,12 +398,12 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
/* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */
if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) {
// courseVirtualCorrection initially used to determine current position relative to course line for later use
int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.yaw - virtualTargetBearing);
int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing);
navCrossTrackError = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection)));
// tracking only active when certain distance and heading conditions are met
if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.yaw)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) {
int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.yaw - posControl.actualState.yaw);
if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) {
int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.bearing - posControl.actualState.cog);
// captureFactor adjusts distance/heading sensitivity balance when closing in on course line.
// Closing distance threashold based on speed and an assumed 1 second response time.
@ -423,7 +423,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
// final courseVirtualCorrection value
courseVirtualCorrection = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle) * courseCorrectionFactor;
virtualTargetBearing = wrap_36000(posControl.activeWaypoint.yaw - courseVirtualCorrection);
virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - courseVirtualCorrection);
}
}
@ -431,7 +431,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
* Calculate NAV heading error
* Units are centidegrees
*/
navHeadingError = wrap_18000(virtualTargetBearing - posControl.actualState.yaw);
navHeadingError = wrap_18000(virtualTargetBearing - posControl.actualState.cog);
// Forced turn direction
// If heading error is close to 180 deg we initiate forced turn and only disable it when heading error goes below 90 deg
@ -461,7 +461,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
const pidControllerFlags_e pidFlags = PID_DTERM_FROM_ERROR | (errorIsDecreasing ? PID_SHRINK_INTEGRATOR : 0);
// Input error in (deg*100), output roll angle (deg*100)
float rollAdjustment = navPidApply2(&posControl.pids.fw_nav, posControl.actualState.yaw + navHeadingError, posControl.actualState.yaw, US2S(deltaMicros),
float rollAdjustment = navPidApply2(&posControl.pids.fw_nav, posControl.actualState.cog + navHeadingError, posControl.actualState.cog, US2S(deltaMicros),
-DEGREES_TO_CENTIDEGREES(navConfig()->fw.max_bank_angle),
DEGREES_TO_CENTIDEGREES(navConfig()->fw.max_bank_angle),
pidFlags);
@ -769,7 +769,7 @@ void calculateFixedWingInitialHoldPosition(fpVector3_t * pos)
void resetFixedWingHeadingController(void)
{
updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl.actualState.yaw));
updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl.actualState.cog));
}
void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags, timeUs_t currentTimeUs)

View file

@ -802,9 +802,9 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs)
static navigationTimer_t posPublishTimer;
/* IMU operates in decidegrees while INAV operates in deg*100
* Use course over ground for fixed wing navigation yaw/"heading" */
int16_t yawValue = isGPSHeadingValid() && STATE(AIRPLANE) ? posEstimator.est.cog : attitude.values.yaw;
updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(yawValue), DECIDEGREES_TO_CENTIDEGREES(posEstimator.est.cog));
* Use course over ground when GPS heading valid */
int16_t cogValue = isGPSHeadingValid() ? posEstimator.est.cog : attitude.values.yaw;
updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw), DECIDEGREES_TO_CENTIDEGREES(cogValue));
/* Position and velocity are published with INAV_POSITION_PUBLISH_RATE_HZ */
if (updateTimer(&posPublishTimer, HZ2US(INAV_POSITION_PUBLISH_RATE_HZ), currentTimeUs)) {

View file

@ -324,9 +324,9 @@ typedef struct {
typedef struct {
fpVector3_t targetPos;
int32_t yaw;
int32_t previousYaw;
timeMs_t lastYawAdjustmentTime;
int32_t course;
int32_t previousCourse;
timeMs_t lastCourseAdjustmentTime;
} navCruise_t;
typedef struct {
@ -445,10 +445,10 @@ bool isMulticopterFlying(void);
navigationFSMStateFlags_t navGetCurrentStateFlags(void);
void setHomePosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlags_t useMask, navigationHomeFlags_t homeFlags);
void setHomePosition(const fpVector3_t * pos, int32_t heading, navSetWaypointFlags_t useMask, navigationHomeFlags_t homeFlags);
void setDesiredPosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlags_t useMask);
void setDesiredSurfaceOffset(float surfaceOffset);
void setDesiredPositionToFarAwayTarget(int32_t yaw, int32_t distance, navSetWaypointFlags_t useMask);
void setDesiredPositionToFarAwayTarget(int32_t yaw, int32_t distance, navSetWaypointFlags_t useMask); // NOT USED
void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAltitudeControllerMode_e mode);
bool isNavHoldPositionActive(void);

View file

@ -138,6 +138,8 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_SCALE 320
/*
* OSD
*/

View file

@ -148,7 +148,13 @@
/*** Timer/PWM output ***/
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#ifdef FOXEERF722V4_X8
#define MAX_PWM_OUTPUT_PORTS 8
#else
#define MAX_PWM_OUTPUT_PORTS 4
#endif
#define USE_DSHOT
#define USE_ESC_SENSOR

View file

@ -203,6 +203,7 @@
#define PINIO1_PIN PE13
#define PINIO2_PIN PB11
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
#define PINIO2_FLAGS PINIO_FLAGS_INVERTED
#else
#define PINIO1_PIN PE13

View file

@ -289,15 +289,25 @@ int16_t Roll angle ( rad / 10000 )
int16_t Yaw angle ( rad / 10000 )
*/
#define DECIDEGREES_TO_RADIANS10000(angle) ((int16_t)(1000.0f * (angle) * RAD))
// convert andgle in decidegree to radians/10000 with reducing angle to +/-180 degree range
static int16_t decidegrees2Radians10000(int16_t angle_decidegree)
{
while (angle_decidegree > 1800) {
angle_decidegree -= 3600;
}
while (angle_decidegree < -1800) {
angle_decidegree += 3600;
}
return (int16_t)(RAD * 1000.0f * angle_decidegree);
}
static void crsfFrameAttitude(sbuf_t *dst)
{
sbufWriteU8(dst, CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC);
crsfSerialize8(dst, CRSF_FRAMETYPE_ATTITUDE);
crsfSerialize16(dst, DECIDEGREES_TO_RADIANS10000(attitude.values.pitch));
crsfSerialize16(dst, DECIDEGREES_TO_RADIANS10000(attitude.values.roll));
crsfSerialize16(dst, DECIDEGREES_TO_RADIANS10000(attitude.values.yaw));
crsfSerialize16(dst, decidegrees2Radians10000(attitude.values.pitch));
crsfSerialize16(dst, decidegrees2Radians10000(attitude.values.roll));
crsfSerialize16(dst, decidegrees2Radians10000(attitude.values.yaw));
}
/*
@ -323,7 +333,7 @@ static void crsfFrameFlightMode(sbuf_t *dst)
}
if (FLIGHT_MODE(FAILSAFE_MODE)) {
flightMode = "!FS!";
} else if (ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) {
} else if (IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) {
flightMode = "HRST";
} else if (FLIGHT_MODE(MANUAL_MODE)) {
flightMode = "MANU";
@ -335,10 +345,10 @@ static void crsfFrameFlightMode(sbuf_t *dst)
flightMode = "CRUZ";
} else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
flightMode = "CRSH";
} else if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) {
flightMode = "AH";
} else if (FLIGHT_MODE(NAV_WP_MODE)) {
flightMode = "WP";
} else if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) {
flightMode = "AH";
} else if (FLIGHT_MODE(ANGLE_MODE)) {
flightMode = "ANGL";
} else if (FLIGHT_MODE(HORIZON_MODE)) {