mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-12 19:10:27 +03:00
Merge branch 'master' into MrD_Make-min-ground-speed-more-accessible
This commit is contained in:
commit
749083ecb6
58 changed files with 1018 additions and 194 deletions
2
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
2
.github/ISSUE_TEMPLATE/Bug_report.md
vendored
|
@ -38,7 +38,7 @@ assignees: ''
|
|||
|
||||
## Additional context
|
||||
<!-- Add any other context about the problem here. -->
|
||||
<!-- Go to CLI, execute `dump` command copy its output to [PasteBin](https://pastebin.com) and provide a link to a paste here -->
|
||||
<!-- Go to CLI, execute `diff` command copy its output to [PasteBin](https://pastebin.com) and provide a link to a paste here -->
|
||||
|
||||
---
|
||||
<!-- PLEASE FILL THIS OUT -->
|
||||
|
|
|
@ -51,7 +51,6 @@ else()
|
|||
endif()
|
||||
endif()
|
||||
|
||||
|
||||
project(INAV VERSION 9.0.0)
|
||||
|
||||
enable_language(ASM)
|
||||
|
|
19
docs/ADSB.md
19
docs/ADSB.md
|
@ -13,6 +13,7 @@ All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/m
|
|||
|
||||
* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested)
|
||||
* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested)
|
||||
* [ADSBee1090](https://pantsforbirds.com/adsbee-1090/) (tested)
|
||||
|
||||
## TT-SC1 settings
|
||||
* download software for ADSB TT-SC1 from https://www.aerobits.pl/product/aero/ , file Micro_ADSB_App-vX.XX.X_win_setup.zip and install it
|
||||
|
@ -24,3 +25,21 @@ All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/m
|
|||
PCB board for TT-SC1-B module https://oshwlab.com/error414/adsb-power-board
|
||||

|
||||
|
||||
## ADSBee 1090 settings
|
||||
* connect to ADSBee1090 via USB and set COMMS_UART to mavlink2 \
|
||||
``
|
||||
AT+PROTOCOL=COMMS_UART,MAVLINK2
|
||||
``\
|
||||
``
|
||||
AT+BAUDRATE=COMMS_UART,115200
|
||||
``\
|
||||
It's recommended to turn of wifi \
|
||||
``
|
||||
AT+ESP32_ENABLE=0
|
||||
``\
|
||||
``
|
||||
AT+SETTINGS=SAVE
|
||||
``
|
||||
* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200
|
||||
* https://pantsforbirds.com/adsbee-1090/quick-start/
|
||||
|
||||
|
|
|
@ -102,6 +102,15 @@ To restore set from preferences use:
|
|||
|
||||
```
|
||||
beeper -PREFERED
|
||||
```
|
||||
|
||||
To activate an external beeper via aux channel switch, assign aux channel and set both:
|
||||
|
||||
```
|
||||
beeper RX_SET
|
||||
beeper MULTI_BEEPS
|
||||
```
|
||||
If MULTI_BEEPS is not set, the beeper will not sound after GPS lock.
|
||||
|
||||
As with other CLI commands, the `save` command is needed to save the new settings.
|
||||
|
||||
|
@ -117,7 +126,5 @@ Passive buzzers are supported on FCs which are designed to work with passive buz
|
|||
Examples of a known-working buzzers.
|
||||
|
||||
* [Hcm1205x Miniature Buzzer 5v](http://www.rapidonline.com/Audio-Visual/Hcm1205x-Miniature-Buzzer-5v-35-0055)
|
||||
* [5V Electromagnetic Active Buzzer Continuous Beep](https://inavflight.com/shop/s/bg/943524)
|
||||
* [Radio Shack Model: 273-074 PC-BOARD 12VDC (3-16v) 70DB PIEZO BUZZER](http://www.radioshack.com/pc-board-12vdc-70db-piezo-buzzer/2730074.html#.VIAtpzHF_Si)
|
||||
* [MultiComp MCKPX-G1205A-3700 TRANSDUCER, THRU-HOLE, 4V, 30MA](http://uk.farnell.com/multicomp/mckpx-g1205a-3700/transducer-thru-hole-4v-30ma/dp/2135914?CMP=i-bf9f-00001000)
|
||||
* [3-24V Piezo Electronic Tone Buzzer Alarm 95DB](https://inavflight.com/shop/s/bg/919348)
|
||||
|
|
|
@ -7,12 +7,15 @@ Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and eve
|
|||
|
||||
As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin.
|
||||
|
||||
Feature can be used to drive external devices. It is also used to simulate [OSD joystick](OSD%20Joystick.md) to control cameras.
|
||||
Feature can be used to drive external devices such as a VTX power switch. Setting the PWM duty cycle to 100% or 0% can
|
||||
provide an extra PINIO pin. It is also used to simulate [OSD joystick](OSD%20Joystick.md) to control cameras.
|
||||
|
||||
PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%:
|
||||
|
||||

|
||||
|
||||
Note that the LED feature needs to be enabled when using the PIN in this mode (feature LED_STRIP).
|
||||
|
||||
There are four modes of operation:
|
||||
- low
|
||||
- high
|
||||
|
@ -88,3 +91,6 @@ To drive power LED with brightness control, Mosfet should be used:
|
|||
|
||||

|
||||
|
||||
# Programming tab example for using the LED pin as a PINIO, such as for turning a VTX or camera on and off
|
||||
!(/docs/assets/images/led-as-pinio.png "led pin as pinio")
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@ General OSD information is in this document. Other documents cover specific OSD-
|
|||
Not all OSDs are created equally. This table shows the differences between the different systems available.
|
||||
|
||||
| OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported |
|
||||
|---------------|----------------|-----------|--------|-----------------|-------------------------|
|
||||
|-----------------------------|----------------|-----------|--------|-----------------|-------------------------|
|
||||
| Analogue PAL | 30 x 16 | X | | | YES |
|
||||
| Analogue NTSC | 30 x 13 | X | | | YES |
|
||||
| PixelOSD | As PAL or NTSC | | X | | YES |
|
||||
|
@ -23,7 +23,8 @@ Not all OSDs are created equally. This table shows the differences between the d
|
|||
| DJI WTFOS | 60 x 22 | X | | X | YES |
|
||||
| HDZero | 50 x 18 | X | | X | YES |
|
||||
| Avatar | 53 x 20 | X | | X | YES |
|
||||
| DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only |
|
||||
| DJI O3 Goggles V2 + WTFOS | 53 x 20 | X | | X | YES |
|
||||
| DJI Goggles 2 and newer | 53 x 20 (HD) | X | | X | YES (no custom fonts) |
|
||||
|
||||
## OSD Elements
|
||||
Here are the OSD Elements provided by INAV.
|
||||
|
|
|
@ -75,7 +75,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
|||
| 26 | Invert Roll | Inverts ROLL axis input for PID/PIFF controller |
|
||||
| 27 | Invert Pitch | Inverts PITCH axis input for PID/PIFF controller |
|
||||
| 28 | Invert Yaw | Inverts YAW axis input for PID/PIFF controller |
|
||||
| 29 | Override Throttlw | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 29 | Override Throttle | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 30 | Set VTx Band | Sets VTX band. Accepted values are `1-5` |
|
||||
| 31 | Set VTx Channel | Sets VTX channel. Accepted values are `1-8` |
|
||||
| 32 | Set OSD Layout | Sets OSD layout. Accepted values are `0-3` |
|
||||
|
@ -98,10 +98,11 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
|||
| 49 | Timer | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. |
|
||||
| 50 | Delta | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. ( \|ΔA\| >= B ) |
|
||||
| 51 | Approx Equals (A ~ B) | `true` if `Operand B` is within 1% of `Operand A`. |
|
||||
| 52 | LED Pin PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes). |
|
||||
| 52 | LED Pin PWM | Value `Operand A` from [`0` : `100`] PWM / PINIO generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes). |
|
||||
| 53 | Disable GPS Sensor Fix | Disables the GNSS sensor fix. For testing GNSS failure. |
|
||||
| 54 | Mag calibration | Trigger a magnetometer calibration. |
|
||||
| 55 | Override Minimum Ground Speed | When active, sets the minimum ground speed to the value specified in `Operand A` [m/s]. Minimum allowed value is set in `nav_min_ground_speed`. Maximum value is `150` |
|
||||
| 55 | Set Gimbal Sensitivity | Scales `Operand A` from [`-16` : `15`]
|
||||
| 56 | Override Minimum Ground Speed | When active, sets the minimum ground speed to the value specified in `Operand A` [m/s]. Minimum allowed value is set in `nav_min_ground_speed`. Maximum value is `150` |
|
||||
|
||||
### Operands
|
||||
|
||||
|
|
|
@ -200,7 +200,7 @@ Note:
|
|||
* It is necessary to update `MSP_SET_RAW_RC` at 5Hz or faster.
|
||||
* `MSP_SET_RAW_RC` uses the defined RC channel map
|
||||
* `MSP_RC` returns `AERT` regardless of channel map
|
||||
* You can combine "real" RC radio and MSP RX by compiling custom firmware with `USE_MSP_RC_OVERRIDE` defined. Then use `msp_override_channels` to set the channels to be overridden.
|
||||
* You can combine "real" RC radio and MSP RX by using `msp_override_channels` to set the channels to be overridden.
|
||||
* The [wiki Remote Control and Management article](https://github.com/iNavFlight/inav/wiki/INAV-Remote-Management,-Control-and-Telemetry) provides more information, including links to 3rd party projects that exercise `MSP_SET_RAW_RC` and `USE_MSP_RC_OVERRIDE`
|
||||
|
||||
## SIM (SITL) Joystick
|
||||
|
|
|
@ -89,3 +89,37 @@ The allowable baud rates are as follows:
|
|||
| 14 | 1500000 |
|
||||
| 15 | 2000000 |
|
||||
| 16 | 2470000 |
|
||||
|
||||
|
||||
### Function numbers as of 2025
|
||||
|
||||
| Function | Number |
|
||||
| -------------------------- | -------------------------------------------------- |
|
||||
| NONE | 0, |
|
||||
| MSP | (1 << 0), // 1 |
|
||||
| GPS | (1 << 1), // 2 |
|
||||
| UNUSED_3 | (1 << 2), // 4 //Was FUNCTION_TELEMETRY_FRSKY |
|
||||
| TELEMETRY_HOTT | (1 << 3), // 8 |
|
||||
| TELEMETRY_LTM | (1 << 4), // 16 |
|
||||
| TELEMETRY_SMARTPORT | (1 << 5), // 32 |
|
||||
| RX_SERIAL | (1 << 6), // 64 |
|
||||
| BLACKBOX | (1 << 7), // 128 |
|
||||
| TELEMETRY_MAVLINK | (1 << 8), // 256 |
|
||||
| TELEMETRY_IBUS | (1 << 9), // 512 |
|
||||
| RCDEVICE | (1 << 10), // 1024 |
|
||||
| VTX_SMARTAUDIO | (1 << 11), // 2048 |
|
||||
| VTX_TRAMP | (1 << 12), // 4096 |
|
||||
| UNUSED_1 | (1 << 13), // 8192: former\ UAV_INTERCONNECT |
|
||||
| OPTICAL_FLOW | (1 << 14), // 16384 |
|
||||
| LOG | (1 << 15), // 32768 |
|
||||
| RANGEFINDER | (1 << 16), // 65536 |
|
||||
| VTX_FFPV | (1 << 17), // 131072 |
|
||||
| ESCSERIAL | (1 << 18), // 262144: this is used for both SERIALSHOT and ESC_SENSOR telemetry |
|
||||
| TELEMETRY_SIM | (1 << 19), // 524288 |
|
||||
| FRSKY_OSD | (1 << 20), // 1048576 |
|
||||
| DJI_HD_OSD | (1 << 21), // 2097152 |
|
||||
| SERVO_SERIAL | (1 << 22), // 4194304 |
|
||||
| TELEMETRY_SMARTPORT_MASTER | (1 << 23), // 8388608 |
|
||||
| UNUSED_2 | (1 << 24), // 16777216 |
|
||||
| MSP_OSD | (1 << 25), // 33554432 |
|
||||
|
||||
|
|
|
@ -3034,7 +3034,7 @@ If enabled, motor will stop when throttle is low on this mixer_profile
|
|||
|
||||
### msp_override_channels
|
||||
|
||||
Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode.
|
||||
Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires the `MSP RC Override` flight mode.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 32 KiB After Width: | Height: | Size: 38 KiB |
BIN
docs/assets/images/led-as-pinio.png
Normal file
BIN
docs/assets/images/led-as-pinio.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 24 KiB |
|
@ -68,3 +68,8 @@ If one of the core developers has the hardware in possession they may opt in and
|
|||
1. Requester is advised to open a feature request to add support for certain hardware to INAV by following [this link](https://github.com/iNavFlight/inav/issues/new/choose)
|
||||
|
||||
2. After opening a feature request, Requester is advised to contact the core development team by [email](mailto:coredev@inavflight.com) mentioning the open feature request and communicate with developer team via email to arrange hardware and specifications delivery.
|
||||
|
||||
|
||||
## See also
|
||||
[Hardware Design Guidelines](https://github.com/iNavFlight/inav/wiki/Hardware-Design-Guidelines)
|
||||
|
||||
|
|
|
@ -23,8 +23,10 @@
|
|||
#ifdef USE_FULL_ASSERT
|
||||
#include "stm32_assert.h"
|
||||
#else
|
||||
#ifndef assert_param
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/** @addtogroup STM32H7xx_LL_Driver
|
||||
* @{
|
||||
|
|
|
@ -22,8 +22,10 @@
|
|||
#ifdef USE_FULL_ASSERT
|
||||
#include "stm32_assert.h"
|
||||
#else
|
||||
#ifndef assert_param
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/** @addtogroup STM32H7xx_LL_Driver
|
||||
* @{
|
||||
|
|
|
@ -118,6 +118,12 @@ void initEEPROM(void)
|
|||
BUILD_BUG_ON(sizeof(configFooter_t) != 2);
|
||||
BUILD_BUG_ON(sizeof(configRecord_t) != 6);
|
||||
|
||||
#ifdef STM32H7A3xx
|
||||
BUILD_BUG_ON(CONFIG_STREAMER_BUFFER_SIZE != 16);
|
||||
#elif defined(STM32H743xx)
|
||||
BUILD_BUG_ON(CONFIG_STREAMER_BUFFER_SIZE != 32);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_IN_EXTERNAL_FLASH)
|
||||
bool eepromLoaded = loadEEPROMFromExternalFlash();
|
||||
if (!eepromLoaded) {
|
||||
|
|
|
@ -27,15 +27,14 @@
|
|||
|
||||
#ifdef CONFIG_IN_EXTERNAL_FLASH
|
||||
#define CONFIG_STREAMER_BUFFER_SIZE M25P16_PAGESIZE // Must match flash device page size
|
||||
typedef uint32_t config_streamer_buffer_align_type_t;
|
||||
#elif defined(STM32H7)
|
||||
#define CONFIG_STREAMER_BUFFER_SIZE 32 // Flash word = 256-bits
|
||||
typedef uint64_t config_streamer_buffer_align_type_t;
|
||||
#define CONFIG_STREAMER_BUFFER_SIZE (FLASH_NB_32BITWORD_IN_FLASHWORD * 4) // Flash word = 256-bits or 128bits, depending on the mcu
|
||||
#else
|
||||
#define CONFIG_STREAMER_BUFFER_SIZE 4
|
||||
typedef uint32_t config_streamer_buffer_align_type_t;
|
||||
#endif
|
||||
|
||||
typedef uint32_t config_streamer_buffer_align_type_t;
|
||||
|
||||
typedef struct config_streamer_s {
|
||||
uintptr_t address;
|
||||
uintptr_t end;
|
||||
|
|
|
@ -22,9 +22,38 @@
|
|||
|
||||
#if defined(STM32H7) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH)
|
||||
|
||||
#if defined(STM32H743xx)
|
||||
static uint32_t getFLASHBankForEEPROM(uint32_t address)
|
||||
{
|
||||
#ifdef DUAL_BANK
|
||||
if (address < (FLASH_BASE + FLASH_BANK_SIZE)) {
|
||||
return FLASH_BANK_1;
|
||||
}
|
||||
|
||||
return FLASH_BANK_2;
|
||||
#else
|
||||
return FLASH_BANK_1;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(STM32H7A3xx)
|
||||
static uint32_t getFLASHSectorForEEPROM(uint32_t address)
|
||||
{
|
||||
uint32_t sector = 0;
|
||||
|
||||
if (address < (FLASH_BASE + FLASH_BANK_SIZE)) {
|
||||
sector = (address - FLASH_BASE) / FLASH_SECTOR_SIZE;
|
||||
} else {
|
||||
sector = (address - (FLASH_BASE + FLASH_BANK_SIZE)) / FLASH_SECTOR_SIZE;
|
||||
}
|
||||
|
||||
if (sector > FLASH_SECTOR_TOTAL) {
|
||||
failureMode(FAILURE_FLASH_WRITE_FAILED);
|
||||
}
|
||||
|
||||
return sector;
|
||||
}
|
||||
#elif defined(STM32H743xx)
|
||||
/* Sectors 0-7 of 128K each */
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors
|
||||
static uint32_t getFLASHSectorForEEPROM(uint32_t address)
|
||||
{
|
||||
if (address <= 0x0801FFFF)
|
||||
|
@ -70,13 +99,14 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
|
|||
return c->err;
|
||||
}
|
||||
|
||||
if (c->address % FLASH_PAGE_SIZE == 0) {
|
||||
if (c->address % FLASH_SECTOR_SIZE == 0) {
|
||||
FLASH_EraseInitTypeDef EraseInitStruct = {
|
||||
.TypeErase = FLASH_TYPEERASE_SECTORS,
|
||||
#ifdef FLASH_VOLTAGE_RANGE_3
|
||||
.VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V
|
||||
.NbSectors = 1,
|
||||
.Banks = FLASH_BANK_1
|
||||
};
|
||||
#endif
|
||||
.NbSectors = 1};
|
||||
EraseInitStruct.Banks = getFLASHBankForEEPROM(c->address);
|
||||
EraseInitStruct.Sector = getFLASHSectorForEEPROM(c->address);
|
||||
|
||||
uint32_t SECTORError;
|
||||
|
|
|
@ -49,7 +49,7 @@ typedef struct pgRegistry_s {
|
|||
uint8_t **ptr; // The pointer to update after loading the record into ram.
|
||||
union {
|
||||
void *ptr; // Pointer to init template
|
||||
pgResetFunc *fn; // Popinter to pgResetFunc
|
||||
pgResetFunc *fn; // Pointer to pgResetFunc
|
||||
} reset;
|
||||
} pgRegistry_t;
|
||||
|
||||
|
|
|
@ -67,6 +67,10 @@ typedef enum SPIDevice {
|
|||
#define SPIDEV_COUNT 4
|
||||
#endif
|
||||
|
||||
#if defined(AT32F43x)
|
||||
typedef spi_type SPI_TypeDef;
|
||||
#endif
|
||||
|
||||
typedef struct SPIDevice_s {
|
||||
#if defined(AT32F43x)
|
||||
spi_type *dev;
|
||||
|
|
|
@ -89,6 +89,11 @@ bool gimbalCommonIsReady(gimbalDevice_t *gimbalDevice)
|
|||
return false;
|
||||
}
|
||||
|
||||
void setGimbalSensitivity(int16_t sensitivity)
|
||||
{
|
||||
gimbalConfigMutable()->sensitivity = sensitivity;
|
||||
}
|
||||
|
||||
#ifdef GIMBAL_UNIT_TEST
|
||||
void taskUpdateGimbal(timeUs_t currentTimeUs)
|
||||
{
|
||||
|
|
|
@ -96,6 +96,7 @@ bool gimbalCommonIsEnabled(void);
|
|||
bool gimbalCommonHtrkIsEnabled(void);
|
||||
|
||||
int16_t gimbalCommonGetPanPwm(const gimbalDevice_t *gimbalDevice);
|
||||
void setGimbalSensitivity(int16_t sensitivity);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -50,7 +50,8 @@ typedef enum {
|
|||
VIDEO_SYSTEM_DJIWTF,
|
||||
VIDEO_SYSTEM_AVATAR,
|
||||
VIDEO_SYSTEM_DJICOMPAT,
|
||||
VIDEO_SYSTEM_DJICOMPAT_HD
|
||||
VIDEO_SYSTEM_DJICOMPAT_HD,
|
||||
VIDEO_SYSTEM_DJI_NATIVE
|
||||
} videoSystem_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -471,7 +471,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode,
|
|||
else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->rx_af);
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->tx_af);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
|
|
|
@ -4190,14 +4190,19 @@ static void cliStatus(char *cmdline)
|
|||
#if defined(USE_OSD)
|
||||
if (armingFlags & ARMING_DISABLED_NAVIGATION_UNSAFE) {
|
||||
navArmingBlocker_e reason = navigationIsBlockingArming(NULL);
|
||||
if (reason & NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR)
|
||||
if (reason == NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR)
|
||||
cliPrintLinef(" %s", OSD_MSG_JUMP_WP_MISCONFIG);
|
||||
if (reason & NAV_ARMING_BLOCKER_MISSING_GPS_FIX) {
|
||||
if (reason == NAV_ARMING_BLOCKER_MISSING_GPS_FIX) {
|
||||
cliPrintLinef(" %s", OSD_MSG_WAITING_GPS_FIX);
|
||||
} else {
|
||||
if (reason & NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE)
|
||||
if (reason == NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE) {
|
||||
if(armingFlags & ARMING_DISABLED_RC_LINK) {
|
||||
cliPrintLinef(" ENABLE RX TO CLEAR NAV");
|
||||
} else {
|
||||
cliPrintLinef(" %s", OSD_MSG_DISABLE_NAV_FIRST);
|
||||
if (reason & NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR)
|
||||
}
|
||||
}
|
||||
if (reason == NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR)
|
||||
cliPrintLinef(" FIRST WP TOO FAR");
|
||||
}
|
||||
}
|
||||
|
|
|
@ -677,7 +677,9 @@ void init(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_VTX_MSP
|
||||
if (feature(FEATURE_OSD)) {
|
||||
vtxMspInit();
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // USE_VTX_CONTROL
|
||||
|
|
|
@ -1737,6 +1737,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP2_COMMON_GET_RADAR_GPS:
|
||||
for (uint8_t i = 0; i < RADAR_MAX_POIS; i++){
|
||||
sbufWriteDataSafe(dst, &radar_pois[i].gps, sizeof(gpsLocation_t));
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -67,7 +67,7 @@ tables:
|
|||
values: ["MAH", "WH"]
|
||||
enum: osd_stats_energy_unit_e
|
||||
- name: osd_video_system
|
||||
values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT"]
|
||||
values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT", "DJI_NATIVE"]
|
||||
enum: videoSystem_e
|
||||
- name: osd_telemetry
|
||||
values: ["OFF", "ON","TEST"]
|
||||
|
@ -770,7 +770,7 @@ groups:
|
|||
field: halfDuplex
|
||||
table: tristate
|
||||
- name: msp_override_channels
|
||||
description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode."
|
||||
description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires the `MSP RC Override` flight mode."
|
||||
default_value: 0
|
||||
field: mspOverrideChannels
|
||||
condition: USE_MSP_RC_OVERRIDE
|
||||
|
@ -4319,18 +4319,21 @@ groups:
|
|||
field: sensitivity
|
||||
min: -16
|
||||
max: 15
|
||||
type: int8_t
|
||||
- name: gimbal_pan_trim
|
||||
field: panTrim
|
||||
description: "Trim gimbal pan center position."
|
||||
default_value: 0
|
||||
min: -500
|
||||
max: 500
|
||||
type: int16_t
|
||||
- name: gimbal_tilt_trim
|
||||
field: tiltTrim
|
||||
description: "Trim gimbal tilt center position."
|
||||
default_value: 0
|
||||
min: -500
|
||||
max: 500
|
||||
type: int16_t
|
||||
- name: gimbal_roll_trim
|
||||
field: rollTrim
|
||||
description: "Trim gimbal roll center position."
|
||||
|
|
|
@ -596,23 +596,29 @@ int16_t angleFreefloatDeadband(int16_t deadband, flight_dynamics_index_t axis)
|
|||
|
||||
static float computePidLevelTarget(flight_dynamics_index_t axis) {
|
||||
// This is ROLL/PITCH, run ANGLE/HORIZON controllers
|
||||
|
||||
// Limit max bank angle for multirotor during Nav mode Angle controlled position adjustment
|
||||
uint16_t maxBankAngle = STATE(MULTIROTOR) && navConfig()->general.flags.user_control_mode == NAV_GPS_ATTI && isAdjustingPosition() ?
|
||||
DEGREES_TO_DECIDEGREES(navConfig()->mc.max_bank_angle) : pidProfile()->max_angle_inclination[axis];
|
||||
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
float angleTarget = pidRcCommandToAngle(getRcCommandOverride(rcCommand, axis), pidProfile()->max_angle_inclination[axis]);
|
||||
float angleTarget = pidRcCommandToAngle(getRcCommandOverride(rcCommand, axis), maxBankAngle);
|
||||
#else
|
||||
float angleTarget = pidRcCommandToAngle(rcCommand[axis], pidProfile()->max_angle_inclination[axis]);
|
||||
float angleTarget = pidRcCommandToAngle(rcCommand[axis], maxBankAngle);
|
||||
#endif
|
||||
|
||||
// Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle
|
||||
if (STATE(AIRPLANE)) {
|
||||
// Automatically pitch down if the throttle is manually controlled and reduced below cruise throttle
|
||||
#ifdef USE_FW_AUTOLAND
|
||||
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle() && !FLIGHT_MODE(NAV_FW_AUTOLAND)) {
|
||||
if (axis == FD_PITCH && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle() && !FLIGHT_MODE(NAV_FW_AUTOLAND)) {
|
||||
#else
|
||||
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) {
|
||||
if (axis == FD_PITCH && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) {
|
||||
#endif
|
||||
angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, navConfig()->fw.minThrottleDownPitchAngle);
|
||||
}
|
||||
|
||||
//PITCH trim applied by a AutoLevel flight mode and manual pitch trimming
|
||||
if (axis == FD_PITCH && STATE(AIRPLANE)) {
|
||||
if (axis == FD_PITCH) {
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 0, angleTarget * 10);
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 1, fixedWingLevelTrim * 10);
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 2, getEstimatedActualVelocity(Z));
|
||||
|
@ -629,6 +635,7 @@ static float computePidLevelTarget(flight_dynamics_index_t axis) {
|
|||
angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim);
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10);
|
||||
}
|
||||
}
|
||||
|
||||
return angleTarget;
|
||||
}
|
||||
|
|
|
@ -494,6 +494,7 @@ displayPort_t* mspOsdDisplayPortInit(const videoSystem_e videoSystem)
|
|||
break;
|
||||
case VIDEO_SYSTEM_DJICOMPAT_HD:
|
||||
case VIDEO_SYSTEM_AVATAR:
|
||||
case VIDEO_SYSTEM_DJI_NATIVE:
|
||||
currentOsdMode = HD_5320;
|
||||
screenRows = AVATAR_ROWS;
|
||||
screenCols = AVATAR_COLS;
|
||||
|
|
|
@ -36,4 +36,6 @@
|
|||
#define MSP2_COMMON_SET_MSP_RC_LINK_STATS 0x100D //in message Sets the MSP RC stats
|
||||
#define MSP2_COMMON_SET_MSP_RC_INFO 0x100E //in message Sets the MSP RC info
|
||||
|
||||
#define MSP2_COMMON_GET_RADAR_GPS 0x100F //get radar position for other planes
|
||||
|
||||
#define MSP2_BETAFLIGHT_BIND 0x3000
|
||||
|
|
|
@ -140,19 +140,14 @@ bool adjustMulticopterAltitudeFromRCInput(void)
|
|||
const int16_t rcThrottleAdjustment = applyDeadbandRescaled(rcCommand[THROTTLE] - altHoldThrottleRCZero, rcControlsConfig()->alt_hold_deadband, -500, 500);
|
||||
|
||||
if (rcThrottleAdjustment) {
|
||||
// set velocity proportional to stick movement
|
||||
float rcClimbRate;
|
||||
/* Set velocity proportional to stick movement
|
||||
* Scale from altHoldThrottleRCZero to maxthrottle or minthrottle to altHoldThrottleRCZero */
|
||||
|
||||
// Make sure we can satisfy max_manual_climb_rate in both up and down directions
|
||||
if (rcThrottleAdjustment > 0) {
|
||||
// Scaling from altHoldThrottleRCZero to maxthrottle
|
||||
rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(getMaxThrottle() - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband);
|
||||
}
|
||||
else {
|
||||
// Scaling from minthrottle to altHoldThrottleRCZero
|
||||
rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(altHoldThrottleRCZero - getThrottleIdleValue() - rcControlsConfig()->alt_hold_deadband);
|
||||
}
|
||||
// Calculate max up or min down limit value scaled for deadband
|
||||
int16_t limitValue = rcThrottleAdjustment > 0 ? getMaxThrottle() : getThrottleIdleValue();
|
||||
limitValue = applyDeadbandRescaled(limitValue - altHoldThrottleRCZero, rcControlsConfig()->alt_hold_deadband, -500, 500);
|
||||
|
||||
int16_t rcClimbRate = ABS(rcThrottleAdjustment) * navConfig()->mc.max_manual_climb_rate / limitValue;
|
||||
updateClimbRateToAltitudeController(rcClimbRate, 0, ROC_TO_ALT_CONSTANT);
|
||||
|
||||
return true;
|
||||
|
|
|
@ -49,6 +49,7 @@
|
|||
#include "flight/mixer_profile.h"
|
||||
#include "flight/wind_estimator.h"
|
||||
#include "drivers/io_port_expander.h"
|
||||
#include "drivers/gimbal_common.h"
|
||||
#include "io/osd_common.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
|
||||
|
@ -343,6 +344,16 @@ static int logicConditionCompute(
|
|||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY:
|
||||
#ifdef USE_SERIAL_GIMBAL
|
||||
setGimbalSensitivity(constrain(operandA, SETTING_GIMBAL_SENSITIVITY_MIN, SETTING_GIMBAL_SENSITIVITY_MAX));
|
||||
return true;
|
||||
break;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
|
||||
case LOGIC_CONDITION_INVERT_ROLL:
|
||||
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL);
|
||||
return true;
|
||||
|
|
|
@ -84,7 +84,8 @@ typedef enum {
|
|||
LOGIC_CONDITION_LED_PIN_PWM = 52,
|
||||
LOGIC_CONDITION_DISABLE_GPS_FIX = 53,
|
||||
LOGIC_CONDITION_RESET_MAG_CALIBRATION = 54,
|
||||
LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED = 55,
|
||||
LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY = 55,
|
||||
LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED = 56,
|
||||
LOGIC_CONDITION_LAST
|
||||
} logicOperation_e;
|
||||
|
||||
|
|
|
@ -45,6 +45,7 @@ enum {
|
|||
CRSF_FRAME_GPS_PAYLOAD_SIZE = 15,
|
||||
CRSF_FRAME_VARIO_SENSOR_PAYLOAD_SIZE = 2,
|
||||
CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8,
|
||||
CRSF_FRAME_BAROMETER_ALTITUDE_PAYLOAD_SIZE = 2,
|
||||
CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10,
|
||||
CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE = 22, // 11 bits per channel * 16 channels = 22 bytes.
|
||||
CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
|
||||
|
@ -86,6 +87,7 @@ typedef enum {
|
|||
CRSF_FRAMETYPE_GPS = 0x02,
|
||||
CRSF_FRAMETYPE_VARIO_SENSOR = 0x07,
|
||||
CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
|
||||
CRSF_FRAMETYPE_BAROMETER_ALTITUDE = 0x09,
|
||||
CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
|
||||
CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
|
||||
CRSF_FRAMETYPE_ATTITUDE = 0x1E,
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -48,6 +49,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
|
||||
|
@ -83,13 +85,15 @@
|
|||
|
||||
serialPort_t *jetiExBusPort;
|
||||
|
||||
uint32_t jetiTimeStampRequest = 0;
|
||||
volatile uint32_t jetiTimeStampRequest = 0;
|
||||
|
||||
volatile bool jetiExBusCanTx = false;
|
||||
|
||||
static uint8_t jetiExBusFramePosition;
|
||||
static uint8_t jetiExBusFrameLength;
|
||||
|
||||
static uint8_t jetiExBusFrameState = EXBUS_STATE_ZERO;
|
||||
uint8_t jetiExBusRequestState = EXBUS_STATE_ZERO;
|
||||
static volatile uint8_t jetiExBusFrameState = EXBUS_STATE_ZERO;
|
||||
volatile uint8_t jetiExBusRequestState = EXBUS_STATE_ZERO;
|
||||
|
||||
// Use max values for ram areas
|
||||
static uint8_t jetiExBusChannelFrame[EXBUS_MAX_CHANNEL_FRAME_SIZE];
|
||||
|
@ -117,16 +121,18 @@ void jetiExBusDecodeChannelFrame(uint8_t *exBusFrame)
|
|||
{
|
||||
uint16_t value;
|
||||
uint8_t frameAddr;
|
||||
uint8_t channelDataLen = exBusFrame[EXBUS_HEADER_LEN - 1];
|
||||
uint8_t receivedChannelCount = MIN((channelDataLen) / 2, JETIEXBUS_CHANNEL_COUNT);
|
||||
|
||||
// Decode header
|
||||
switch (((uint16_t)exBusFrame[EXBUS_HEADER_SYNC] << 8) | ((uint16_t)exBusFrame[EXBUS_HEADER_REQ])) {
|
||||
|
||||
case EXBUS_CHANNELDATA_DATA_REQUEST: // not yet specified
|
||||
case EXBUS_CHANNELDATA:
|
||||
for (uint8_t i = 0; i < JETIEXBUS_CHANNEL_COUNT; i++) {
|
||||
frameAddr = EXBUS_HEADER_LEN + i * 2;
|
||||
for (uint8_t i = 0; i < receivedChannelCount; i++) {
|
||||
frameAddr = EXBUS_HEADER_LEN + (i * 2);
|
||||
value = ((uint16_t)exBusFrame[frameAddr + 1]) << 8;
|
||||
value += (uint16_t)exBusFrame[frameAddr];
|
||||
value |= (uint16_t)exBusFrame[frameAddr];
|
||||
// Convert to internal format
|
||||
jetiExBusChannelData[i] = value >> 3;
|
||||
}
|
||||
|
@ -152,7 +158,7 @@ void jetiExBusFrameReset(void)
|
|||
*/
|
||||
|
||||
// Receive ISR callback
|
||||
static void jetiExBusDataReceive(uint16_t c, void *data)
|
||||
FAST_CODE NOINLINE static void jetiExBusDataReceive(uint16_t c, void *data)
|
||||
{
|
||||
UNUSED(data);
|
||||
|
||||
|
@ -189,6 +195,14 @@ static void jetiExBusDataReceive(uint16_t c, void *data)
|
|||
}
|
||||
}
|
||||
|
||||
if(jetiExBusFramePosition == 1) {
|
||||
if(c == 0x01) {
|
||||
jetiExBusCanTx = true;
|
||||
} else {
|
||||
jetiExBusCanTx = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (jetiExBusFramePosition == jetiExBusFrameMaxSize) {
|
||||
// frame overrun
|
||||
jetiExBusFrameReset();
|
||||
|
@ -204,7 +218,6 @@ static void jetiExBusDataReceive(uint16_t c, void *data)
|
|||
|
||||
// Check the header for the message length
|
||||
if (jetiExBusFramePosition == EXBUS_HEADER_LEN) {
|
||||
|
||||
if ((jetiExBusFrameState == EXBUS_STATE_IN_PROGRESS) && (jetiExBusFrame[EXBUS_HEADER_MSG_LEN] <= EXBUS_MAX_CHANNEL_FRAME_SIZE)) {
|
||||
jetiExBusFrameLength = jetiExBusFrame[EXBUS_HEADER_MSG_LEN];
|
||||
return;
|
||||
|
@ -223,9 +236,12 @@ static void jetiExBusDataReceive(uint16_t c, void *data)
|
|||
|
||||
// Done?
|
||||
if (jetiExBusFrameLength == jetiExBusFramePosition) {
|
||||
if (jetiExBusFrameState == EXBUS_STATE_IN_PROGRESS)
|
||||
if (jetiExBusFrameState == EXBUS_STATE_IN_PROGRESS) {
|
||||
jetiExBusFrameState = EXBUS_STATE_RECEIVED;
|
||||
jetiExBusRequestState = EXBUS_STATE_ZERO;
|
||||
}
|
||||
if (jetiExBusRequestState == EXBUS_STATE_IN_PROGRESS) {
|
||||
jetiExBusFrameState = EXBUS_STATE_ZERO;
|
||||
jetiExBusRequestState = EXBUS_STATE_RECEIVED;
|
||||
jetiTimeStampRequest = now;
|
||||
}
|
||||
|
@ -268,6 +284,8 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
|
|||
rxRuntimeConfig->rcReadRawFn = jetiExBusReadRawRC;
|
||||
rxRuntimeConfig->rcFrameStatusFn = jetiExBusFrameStatus;
|
||||
|
||||
memset(jetiExBusChannelData, 0, sizeof(uint16_t) * JETIEXBUS_CHANNEL_COUNT);
|
||||
|
||||
jetiExBusFrameReset();
|
||||
|
||||
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#define EXBUS_CRC_LEN 2
|
||||
#define EXBUS_OVERHEAD (EXBUS_HEADER_LEN + EXBUS_CRC_LEN)
|
||||
#define EXBUS_MAX_CHANNEL_FRAME_SIZE (EXBUS_HEADER_LEN + JETIEXBUS_CHANNEL_COUNT*2 + EXBUS_CRC_LEN)
|
||||
#define EXBUS_MAX_REQUEST_FRAME_SIZE 9
|
||||
#define EXBUS_MAX_REQUEST_FRAME_SIZE 32 //9
|
||||
|
||||
#define EXBUS_EX_REQUEST (0x3A)
|
||||
|
||||
|
@ -42,11 +42,13 @@ enum {
|
|||
EXBUS_STATE_PROCESSED
|
||||
};
|
||||
|
||||
extern uint8_t jetiExBusRequestState;
|
||||
extern uint32_t jetiTimeStampRequest;
|
||||
extern volatile uint8_t jetiExBusRequestState;
|
||||
extern volatile uint32_t jetiTimeStampRequest;
|
||||
extern uint8_t jetiExBusRequestFrame[EXBUS_MAX_REQUEST_FRAME_SIZE];
|
||||
struct serialPort_s;
|
||||
extern struct serialPort_s *jetiExBusPort;
|
||||
|
||||
extern volatile bool jetiExBusCanTx;
|
||||
|
||||
uint16_t jetiExBusCalcCRC16(uint8_t *pt, uint8_t msgLen);
|
||||
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
1
src/main/target/DAKEFPVF722X8/CMakeLists.txt
Normal file
1
src/main/target/DAKEFPVF722X8/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(DAKEFPVF722X8)
|
32
src/main/target/DAKEFPVF722X8/config.c
Normal file
32
src/main/target/DAKEFPVF722X8/config.c
Normal file
|
@ -0,0 +1,32 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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,
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/piniobox.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
|
||||
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
|
||||
}
|
36
src/main/target/DAKEFPVF722X8/target.c
Normal file
36
src/main/target/DAKEFPVF722X8/target.c
Normal file
|
@ -0,0 +1,36 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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,
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include <platform.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1, 4, 6)
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1, 0, 6)
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(1, 1, 6),D(1, 3, 6)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 D(2, 6, 0), D(2, 1, 6), D(2, 3, 6)
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 D(2, 6, 0), D(2, 2, 6)
|
||||
DEF_TIM(TIM1, CH3, PA10,TIM_USE_OUTPUT_AUTO, 0, 1), // S6 D(2, 6, 0), D(2, 6, 6)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(2, 4, 7), D(2, 2, 0)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(2, 7, 7)
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LEDStrip D(1, 5, 3)
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
183
src/main/target/DAKEFPVF722X8/target.h
Normal file
183
src/main/target/DAKEFPVF722X8/target.h
Normal file
|
@ -0,0 +1,183 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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,
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "DAK7"
|
||||
#define USBD_PRODUCT_STRING "DAKEFPV F722X8"
|
||||
|
||||
#define LED0 PA15
|
||||
|
||||
#define BEEPER PC3
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// Buses
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define DEFAULT_I2C_BUS BUS_I2C1
|
||||
|
||||
// GYRO
|
||||
#define USE_IMU_MPU6500
|
||||
#define IMU_MPU6500_ALIGN CW90_DEG
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_EXTI_PIN PC4
|
||||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW90_DEG
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define IMU_ICM42605_ALIGN CW90_DEG
|
||||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
#define ICM42605_CS_PIN PA4
|
||||
#define ICM42605_EXTI_PIN PC4
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW90_DEG
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_EXTI_PIN PC4
|
||||
|
||||
#define USE_IMU_ICM42688P
|
||||
#define IMU_ICM42688P_ALIGN CW90_DEG
|
||||
#define ICM42688P_CS_PIN PA4
|
||||
#define ICM42688P_EXTI_PIN PC4
|
||||
#define ICM42688P_SPI_BUS BUS_SPI1
|
||||
|
||||
// M25P256 flash
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PB2
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
// OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// CAMERA_CONTROL
|
||||
#define CAMERA_CONTROL_PIN PB0
|
||||
|
||||
// Serial ports
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PB6
|
||||
#define UART1_TX_PIN PB7
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PD8
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC11
|
||||
#define UART4_TX_PIN PC10
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_RX_PIN PD2
|
||||
#define UART5_TX_PIN PC12
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_CRSF
|
||||
#define SERIALRX_UART SERIAL_PORT_USART5
|
||||
#define GPS_UART SERIAL_PORT_USART1
|
||||
|
||||
//Baro
|
||||
#define USE_BARO
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_DPS310
|
||||
#define BARO_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
// Mag
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_MSP
|
||||
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
// unkonw
|
||||
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
// ADC
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC2
|
||||
#define ADC_CHANNEL_3_PIN PC0
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
#define ADC1_DMA_STREAM DMA2_Stream3
|
||||
#define VBAT_SCALE_DEFAULT 1600
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_LED_STRIP | FEATURE_GPS)
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA0
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
|
||||
// PINIO
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PB1 // 9Vsw
|
||||
#define PINIO2_PIN PB10 // Camera switcher
|
|
@ -1,2 +1,3 @@
|
|||
target_stm32f405xg(MATEKF405)
|
||||
target_stm32f405xg(MATEKF405OSD)
|
||||
target_stm32f405xg(MATEKF405MINI)
|
||||
|
|
|
@ -53,15 +53,7 @@
|
|||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#ifdef MATEKF405OSD
|
||||
// *************** SD Card **************************
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_BUS BUS_SPI3
|
||||
#define SDCARD_CS_PIN PC1
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#else
|
||||
#ifdef MATEKF405MINI
|
||||
// *************** M25P256 flash ********************
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
@ -69,6 +61,14 @@
|
|||
#define M25P16_CS_PIN PC0
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#else
|
||||
// *************** SD Card **************************
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_BUS BUS_SPI3
|
||||
#define SDCARD_CS_PIN PC1
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#endif
|
||||
|
||||
// *************** OSD *****************************
|
||||
|
@ -173,11 +173,7 @@
|
|||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#ifdef MATEKF405
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX )
|
||||
#else
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
|
||||
#endif
|
||||
#define CURRENT_METER_SCALE 179
|
||||
|
||||
#define USE_LED_STRIP
|
||||
|
|
2
src/main/target/ORBITF435/CMakeLists.txt
Normal file
2
src/main/target/ORBITF435/CMakeLists.txt
Normal file
|
@ -0,0 +1,2 @@
|
|||
target_at32f43x_xGT7(ORBITF435)
|
||||
target_at32f43x_xGT7(ORBITF435_SD)
|
67
src/main/target/ORBITF435/config.c
Normal file
67
src/main/target/ORBITF435/config.c
Normal file
|
@ -0,0 +1,67 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute 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 file 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/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <platform.h>
|
||||
|
||||
#include "fc/fc_msp_box.h"
|
||||
#include "io/piniobox.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_ESCSERIAL;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_GPS;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_RX_SERIAL;
|
||||
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; //VTX power switch
|
||||
}
|
52
src/main/target/ORBITF435/target.c
Normal file
52
src/main/target/ORBITF435/target.c
Normal file
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute 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 file 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/.
|
||||
*/
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42688_SPI_BUS, ICM42688_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42688_ALIGN);
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TMR3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 4), // M1
|
||||
DEF_TIM(TMR3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 5), // M2
|
||||
DEF_TIM(TMR2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 2), // M3
|
||||
DEF_TIM(TMR2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 3), // M4
|
||||
DEF_TIM(TMR2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // M5
|
||||
DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 6), // M6
|
||||
DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 7), // M7
|
||||
DEF_TIM(TMR2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 1), // M8
|
||||
|
||||
//DEF_TIM(TMR9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
//DEF_TIM(TMR12, CH1, PB14, TIM_USE_CAMERA_CONTROL, 0, -1), // Camera Control
|
||||
DEF_TIM(TMR5, CH1, PA0, TIM_USE_LED , 0, 8) //2812LED
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
193
src/main/target/ORBITF435/target.h
Normal file
193
src/main/target/ORBITF435/target.h
Normal file
|
@ -0,0 +1,193 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute 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 file 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
|
||||
|
||||
#ifdef ORBITF435
|
||||
#define TARGET_BOARD_IDENTIFIER "ORB4"
|
||||
#define USBD_PRODUCT_STRING "ORBITF435"
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "ORB4SD"
|
||||
#define USBD_PRODUCT_STRING "ORBITF435_SD"
|
||||
#endif
|
||||
|
||||
/*** Indicators ***/
|
||||
#define LED0 PC13 //Blue
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
/*** PINIO ***/
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC8
|
||||
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
#define USB_DETECT_PIN PC9
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_UART4
|
||||
#define USE_UART5
|
||||
#define USE_UART6
|
||||
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define INVERTER_PIN_UART2_RX PB2
|
||||
|
||||
#define UART3_TX_PIN PC10 // No connection
|
||||
#define UART3_RX_PIN PC11 // ESC TLM
|
||||
|
||||
#define UART4_TX_PIN PH3
|
||||
#define UART4_RX_PIN PH2
|
||||
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define SERIAL_PORT_COUNT 7 //VCP, UART1, UART2, UART3, UART4, UART5, UART6
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
// *************** Gyro & ACC **********************
|
||||
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_IMU_ICM42605 //Using ICM42688
|
||||
#define IMU_ICM42688_ALIGN CW270_DEG
|
||||
#define ICM42688_CS_PIN PA4
|
||||
#define ICM42688_SPI_BUS BUS_SPI1
|
||||
|
||||
// *************** I2C(Baro & I2C) **************************
|
||||
#define USE_I2C
|
||||
#define USE_BARO
|
||||
#define USE_MAG
|
||||
#define USE_RANGEFINDER
|
||||
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** Internal SD card && FLASH **************************
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#if defined(ORBITF435_SD)
|
||||
//SDCARD Definations
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_BUS BUS_SPI3
|
||||
#define SDCARD_CS_PIN PC14
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PA8
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#else
|
||||
//FLASHFS Definations
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PB15
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#endif
|
||||
|
||||
// *************** OSD *****************************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define USE_OSD
|
||||
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PC2
|
||||
#define SPI2_MOSI_PIN PC3
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** ADC *****************************
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC5
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define VBAT_SCALE_DEFAULT 1010
|
||||
#define CURRENT_METER_SCALE 125
|
||||
|
||||
// *************** LED *****************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA0
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
|
||||
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
#define USE_ESCSERIAL
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_RPM_FILTER
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 11
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE BIT(2)
|
||||
#define TARGET_IO_PORTH (BIT(1)|BIT(2)|BIT(3))
|
|
@ -25,12 +25,12 @@
|
|||
#include "drivers/timer_def_stm32f4xx.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 D(2,1,6) UP256
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2,7,7) UP217
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(2,2,0) UP217
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2,7,7) UP217
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 D(2,1,6) UP256
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(2,6,0) UP256
|
||||
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2,6,0) UP256
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2,6,0) UP256
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,7,3) UP173
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,6,3) UP173
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1,5,3) UP173
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define IMU_ICM42605_ALIGN CW180_DEG
|
||||
#define IMU_ICM42605_ALIGN CW270_DEG_FLIP
|
||||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
#define ICM42605_CS_PIN PC14
|
||||
|
||||
|
@ -130,6 +130,7 @@
|
|||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PA4
|
||||
#define PINIO2_PIN PB5
|
||||
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
|
|
|
@ -32,10 +32,10 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro1_mpu6000, DEVHW_MPU6000, GYRO1_SPI_BUS, GYRO1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro1_icm42688, DEVHW_ICM42605, GYRO1_SPI_BUS, GYRO1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro2_mpu6000, DEVHW_MPU6000, GYRO2_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro2_icm42688, DEVHW_ICM42605, GYRO2_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro1_mpu6000, DEVHW_MPU6000, GYRO1_SPI_BUS, GYRO1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_1_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro1_icm42688, DEVHW_ICM42605, GYRO1_SPI_BUS, GYRO1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_1_ICM42605_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro2_mpu6000, DEVHW_MPU6000, GYRO2_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_gyro2_icm42688, DEVHW_ICM42605, GYRO2_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ICM42605_ALIGN);
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
|
|
|
@ -98,13 +98,15 @@
|
|||
#define GYRO1_SPI_BUS BUS_SPI1
|
||||
#define GYRO1_CS_PIN PC15
|
||||
#define GYRO2_SPI_BUS BUS_SPI4
|
||||
#define GYRO2_CS_PIN PC13
|
||||
#define GYRO2_CS_PIN PE11
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG_FLIP
|
||||
#define IMU_1_MPU6000_ALIGN CW0_DEG_FLIP
|
||||
#define IMU_2_MPU6000_ALIGN CW90_DEG_FLIP
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define IMU_ICM42605_ALIGN CW90_DEG_FLIP
|
||||
#define IMU_1_ICM42605_ALIGN CW90_DEG_FLIP
|
||||
#define IMU_2_ICM42605_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
|
|
|
@ -155,7 +155,7 @@
|
|||
#define USE_TELEMETRY_JETIEXBUS
|
||||
// These are rather exotic serial protocols
|
||||
#define USE_RX_MSP
|
||||
//#define USE_MSP_RC_OVERRIDE
|
||||
#define USE_MSP_RC_OVERRIDE
|
||||
#define USE_SERIALRX_CRSF
|
||||
#define USE_SERIAL_PASSTHROUGH
|
||||
#define NAV_MAX_WAYPOINTS 120
|
||||
|
|
|
@ -258,6 +258,33 @@ static void crsfFrameBatterySensor(sbuf_t *dst)
|
|||
crsfSerialize8(dst, batteryRemainingPercentage);
|
||||
}
|
||||
|
||||
const int32_t ALT_MIN_DM = 10000;
|
||||
const int32_t ALT_THRESHOLD_DM = 0x8000 - ALT_MIN_DM;
|
||||
const int32_t ALT_MAX_DM = 0x7ffe * 10 - 5;
|
||||
|
||||
/*
|
||||
0x09 Barometer altitude and vertical speed
|
||||
Payload:
|
||||
uint16_t altitude_packed ( dm - 10000 )
|
||||
*/
|
||||
static void crsfBarometerAltitude(sbuf_t *dst)
|
||||
{
|
||||
int32_t altitude_dm = lrintf(getEstimatedActualPosition(Z) / 10);
|
||||
uint16_t altitude_packed;
|
||||
if (altitude_dm < -ALT_MIN_DM) {
|
||||
altitude_packed = 0;
|
||||
} else if (altitude_dm > ALT_MAX_DM) {
|
||||
altitude_packed = 0xfffe;
|
||||
} else if (altitude_dm < ALT_THRESHOLD_DM) {
|
||||
altitude_packed = altitude_dm + ALT_MIN_DM;
|
||||
} else {
|
||||
altitude_packed = ((altitude_dm + 5) / 10) | 0x8000;
|
||||
}
|
||||
sbufWriteU8(dst, CRSF_FRAME_BAROMETER_ALTITUDE_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC);
|
||||
crsfSerialize8(dst, CRSF_FRAMETYPE_BAROMETER_ALTITUDE);
|
||||
crsfSerialize16(dst, altitude_packed);
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
CRSF_ACTIVE_ANTENNA1 = 0,
|
||||
CRSF_ACTIVE_ANTENNA2 = 1
|
||||
|
@ -415,6 +442,7 @@ typedef enum {
|
|||
CRSF_FRAME_FLIGHT_MODE_INDEX,
|
||||
CRSF_FRAME_GPS_INDEX,
|
||||
CRSF_FRAME_VARIO_SENSOR_INDEX,
|
||||
CRSF_FRAME_BAROMETER_ALTITUDE_INDEX,
|
||||
CRSF_SCHEDULE_COUNT_MAX
|
||||
} crsfFrameTypeIndex_e;
|
||||
|
||||
|
@ -481,6 +509,11 @@ static void processCrsf(void)
|
|||
crsfFrameVarioSensor(dst);
|
||||
crsfFinalize(dst);
|
||||
}
|
||||
if (currentSchedule & BV(CRSF_FRAME_BAROMETER_ALTITUDE_INDEX)) {
|
||||
crsfInitializeFrame(dst);
|
||||
crsfBarometerAltitude(dst);
|
||||
crsfFinalize(dst);
|
||||
}
|
||||
#endif
|
||||
crsfScheduleIndex = (crsfScheduleIndex + 1) % crsfScheduleCount;
|
||||
}
|
||||
|
@ -514,6 +547,11 @@ void initCrsfTelemetry(void)
|
|||
if (sensors(SENSOR_BARO) || (STATE(FIXED_WING_LEGACY) && feature(FEATURE_GPS))) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX);
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_BARO
|
||||
if (sensors(SENSOR_BARO)) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_BAROMETER_ALTITUDE_INDEX);
|
||||
}
|
||||
#endif
|
||||
crsfScheduleCount = (uint8_t)index;
|
||||
}
|
||||
|
|
|
@ -145,7 +145,15 @@ const exBusSensor_t jetiExSensors[] = {
|
|||
{"G-Force Y", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
||||
{"G-Force Z", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
||||
{"RPM", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"Trip Distance", "m", EX_TYPE_22b, DECIMAL_MASK(1)}
|
||||
{"Trip Distance", "m", EX_TYPE_22b, DECIMAL_MASK(1)},
|
||||
{"DEBUG0", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG1", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG2", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG3", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG4", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG5", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG6", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||
{"DEBUG7", "", EX_TYPE_22b, DECIMAL_MASK(0)}
|
||||
};
|
||||
|
||||
// after every 15 sensors increment the step by 2 (e.g. ...EX_VAL15, EX_VAL16 = 17) to skip the device description
|
||||
|
@ -172,6 +180,14 @@ enum exSensors_e {
|
|||
EX_GFORCE_Z,
|
||||
EX_RPM,
|
||||
EX_TRIP_DISTANCE,
|
||||
EX_DEBUG0,
|
||||
EX_DEBUG1,
|
||||
EX_DEBUG2,
|
||||
EX_DEBUG3,
|
||||
EX_DEBUG4,
|
||||
EX_DEBUG5,
|
||||
EX_DEBUG6,
|
||||
EX_DEBUG7
|
||||
};
|
||||
|
||||
union{
|
||||
|
@ -183,8 +199,7 @@ union{
|
|||
|
||||
#define JETI_EX_SENSOR_COUNT (ARRAYLEN(jetiExSensors))
|
||||
|
||||
static uint8_t jetiExBusTelemetryFrame[40];
|
||||
static uint8_t jetiExBusTransceiveState = EXBUS_TRANS_RX;
|
||||
static uint8_t jetiExBusTelemetryFrame[JETI_EXBUS_TELEMETRY_FRAME_LEN];
|
||||
static uint8_t firstActiveSensor = 0;
|
||||
static uint32_t exSensorEnabled = 0;
|
||||
|
||||
|
@ -283,6 +298,17 @@ void initJetiExBusTelemetry(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (debugMode != DEBUG_NONE) {
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG0);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG1);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG2);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG3);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG4);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG5);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG6);
|
||||
bitArraySet(&exSensorEnabled, EX_DEBUG7);
|
||||
}
|
||||
|
||||
firstActiveSensor = getNextActiveSensor(0); // find the first active sensor
|
||||
}
|
||||
|
||||
|
@ -422,6 +448,23 @@ int32_t getSensorValue(uint8_t sensor)
|
|||
case EX_TRIP_DISTANCE:
|
||||
return getTotalTravelDistance() / 10;
|
||||
|
||||
case EX_DEBUG0:
|
||||
return debug[0];
|
||||
case EX_DEBUG1:
|
||||
return debug[1];
|
||||
case EX_DEBUG2:
|
||||
return debug[2];
|
||||
case EX_DEBUG3:
|
||||
return debug[3];
|
||||
case EX_DEBUG4:
|
||||
return debug[4];
|
||||
case EX_DEBUG5:
|
||||
return debug[5];
|
||||
case EX_DEBUG6:
|
||||
return debug[6];
|
||||
case EX_DEBUG7:
|
||||
return debug[7];
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
@ -503,12 +546,16 @@ void checkJetiExBusTelemetryState(void)
|
|||
return;
|
||||
}
|
||||
|
||||
void handleJetiExBusTelemetry(void)
|
||||
void NOINLINE handleJetiExBusTelemetry(void)
|
||||
{
|
||||
static uint16_t framesLost = 0; // only for debug
|
||||
static uint8_t item = 0;
|
||||
uint32_t timeDiff;
|
||||
|
||||
if(!jetiExBusCanTx) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Check if we shall reset frame position due to time
|
||||
if (jetiExBusRequestState == EXBUS_STATE_RECEIVED) {
|
||||
|
||||
|
@ -523,7 +570,6 @@ void handleJetiExBusTelemetry(void)
|
|||
|
||||
if ((jetiExBusRequestFrame[EXBUS_HEADER_DATA_ID] == EXBUS_EX_REQUEST) && (jetiExBusCalcCRC16(jetiExBusRequestFrame, jetiExBusRequestFrame[EXBUS_HEADER_MSG_LEN]) == 0)) {
|
||||
if (serialRxBytesWaiting(jetiExBusPort) == 0) {
|
||||
jetiExBusTransceiveState = EXBUS_TRANS_TX;
|
||||
item = sendJetiExBusTelemetry(jetiExBusRequestFrame[EXBUS_HEADER_PACKET_ID], item);
|
||||
jetiExBusRequestState = EXBUS_STATE_PROCESSED;
|
||||
return;
|
||||
|
@ -534,14 +580,8 @@ void handleJetiExBusTelemetry(void)
|
|||
}
|
||||
}
|
||||
|
||||
// check the state if transmit is ready
|
||||
if (jetiExBusTransceiveState == EXBUS_TRANS_IS_TX_COMPLETED) {
|
||||
if (isSerialTransmitBufferEmpty(jetiExBusPort)) {
|
||||
jetiExBusTransceiveState = EXBUS_TRANS_RX;
|
||||
jetiExBusRequestState = EXBUS_STATE_ZERO;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t sendJetiExBusTelemetry(uint8_t packetID, uint8_t item)
|
||||
{
|
||||
|
@ -587,7 +627,7 @@ uint8_t sendJetiExBusTelemetry(uint8_t packetID, uint8_t item)
|
|||
}
|
||||
|
||||
serialWriteBuf(jetiExBusPort, jetiExBusTelemetryFrame, jetiExBusTelemetryFrame[EXBUS_HEADER_MSG_LEN]);
|
||||
jetiExBusTransceiveState = EXBUS_TRANS_IS_TX_COMPLETED;
|
||||
jetiExBusCanTx = false;
|
||||
|
||||
return item;
|
||||
}
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define JETI_EXBUS_TELEMETRY_FRAME_LEN 128
|
||||
|
||||
void initJetiExBusTelemetry(void);
|
||||
void checkJetiExBusTelemetryState(void);
|
||||
void handleJetiExBusTelemetry(void);
|
||||
|
|
|
@ -212,9 +212,9 @@ void ltm_sframe(sbuf_t *dst)
|
|||
void ltm_aframe(sbuf_t *dst)
|
||||
{
|
||||
sbufWriteU8(dst, 'A');
|
||||
sbufWriteU16(dst, DECIDEGREES_TO_DEGREES(attitude.values.pitch));
|
||||
sbufWriteU16(dst, DECIDEGREES_TO_DEGREES(attitude.values.roll));
|
||||
sbufWriteU16(dst, DECIDEGREES_TO_DEGREES(attitude.values.yaw));
|
||||
sbufWriteU16(dst, (int16_t)DECIDEGREES_TO_DEGREES(attitude.values.pitch));
|
||||
sbufWriteU16(dst, (int16_t)DECIDEGREES_TO_DEGREES(attitude.values.roll));
|
||||
sbufWriteU16(dst, (int16_t)DECIDEGREES_TO_DEGREES(attitude.values.yaw));
|
||||
}
|
||||
|
||||
#if defined(USE_GPS)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue