diff --git a/CMakeLists.txt b/CMakeLists.txt index 171bb4df3f..6183069ba1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -51,8 +51,7 @@ else() endif() endif() - -project(INAV VERSION 9.0.0) +project(INAV VERSION 8.0.1) enable_language(ASM) diff --git a/docs/ADSB.md b/docs/ADSB.md index 933cb264cd..3a36d1aa34 100644 --- a/docs/ADSB.md +++ b/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 ![TT-SC1 settings](Screenshots/ADSB_TTSC01_settings.png) +## 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/ + diff --git a/docs/OSD.md b/docs/OSD.md index b43da690b6..1b86538718 100644 --- a/docs/OSD.md +++ b/docs/OSD.md @@ -23,8 +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. diff --git a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_mdma.c b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_mdma.c index c57e98d3a2..dcd5f41a6b 100644 --- a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_mdma.c +++ b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_mdma.c @@ -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 * @{ diff --git a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_rcc.c b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_rcc.c index e7b85d92d6..7aa7d509dd 100644 --- a/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_rcc.c +++ b/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_rcc.c @@ -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 * @{ diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index 6d11c1804d..6c1dfc3dc7 100755 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -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) { diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index 6a598cc9e4..2654d48f70 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -55,7 +55,7 @@ int config_streamer_write(config_streamer_t *c, const uint8_t *p, uint32_t size) return -1; } - for (const uint8_t *pat = p; pat != (uint8_t*)p + size; pat++) { + for (const uint8_t *pat = p; pat != (uint8_t *)p + size; pat++) { c->buffer.b[c->at++] = *pat; if (c->at == sizeof(c->buffer)) { @@ -81,7 +81,7 @@ int config_streamer_flush(config_streamer_t *c) c->err = config_streamer_impl_write_word(c, &c->buffer.w); c->at = 0; } - return c-> err; + return c->err; } int config_streamer_finish(config_streamer_t *c) @@ -91,4 +91,4 @@ int config_streamer_finish(config_streamer_t *c) c->unlocked = false; } return c->err; -} +} \ No newline at end of file diff --git a/src/main/config/config_streamer.h b/src/main/config/config_streamer.h index 33c0954874..2c13a975d8 100644 --- a/src/main/config/config_streamer.h +++ b/src/main/config/config_streamer.h @@ -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; diff --git a/src/main/config/config_streamer_stm32h7.c b/src/main/config/config_streamer_stm32h7.c index baa41ea92b..60940daf04 100644 --- a/src/main/config/config_streamer_stm32h7.c +++ b/src/main/config/config_streamer_stm32h7.c @@ -15,16 +15,45 @@ * along with Cleanflight. If not, see . */ -#include -#include "platform.h" -#include "drivers/system.h" -#include "config/config_streamer.h" + #include + #include "platform.h" + #include "drivers/system.h" + #include "config/config_streamer.h" + + #if defined(STM32H7) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH) -#if defined(STM32H7) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH) +static uint32_t getFLASHBankForEEPROM(uint32_t address) +{ +#ifdef DUAL_BANK + if (address < (FLASH_BASE + FLASH_BANK_SIZE)) { + return FLASH_BANK_1; + } -#if defined(STM32H743xx) + 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) @@ -49,9 +78,9 @@ static uint32_t getFLASHSectorForEEPROM(uint32_t address) } } #elif defined(STM32H750xx) -# error "STM32750xx only has one flash page which contains the bootloader, no spare flash pages available, use external storage for persistent config or ram for target testing" +#error "STM32750xx only has one flash page which contains the bootloader, no spare flash pages available, use external storage for persistent config or ram for target testing" #else -# error "Unsupported CPU!" +#error "Unsupported CPU!" #endif void config_streamer_impl_unlock(void) @@ -70,30 +99,31 @@ 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, - .VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V - .NbSectors = 1, - .Banks = FLASH_BANK_1 - }; - EraseInitStruct.Sector = getFLASHSectorForEEPROM(c->address); - - uint32_t SECTORError; - const HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError); - if (status != HAL_OK) { - return -1; - } - } - - // On H7 HAL_FLASH_Program takes data address, not the raw word value - const HAL_StatusTypeDef status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_FLASHWORD, c->address, (uint32_t)buffer); - if (status != HAL_OK) { - return -2; - } - - c->address += CONFIG_STREAMER_BUFFER_SIZE; - return 0; -} - + .TypeErase = FLASH_TYPEERASE_SECTORS, +#ifdef FLASH_VOLTAGE_RANGE_3 + .VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V #endif + .NbSectors = 1}; + EraseInitStruct.Banks = getFLASHBankForEEPROM(c->address); + EraseInitStruct.Sector = getFLASHSectorForEEPROM(c->address); + + uint32_t SECTORError; + const HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError); + if (status != HAL_OK) { + return -1; + } + } + + // On H7 HAL_FLASH_Program takes data address, not the raw word value + const HAL_StatusTypeDef status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_FLASHWORD, c->address, (uint32_t)buffer); + if (status != HAL_OK) { + return -2; + } + + c->address += CONFIG_STREAMER_BUFFER_SIZE; + return 0; + } + +#endif \ No newline at end of file diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 88bbbf286d..ff68798400 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -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; diff --git a/src/main/drivers/osd.h b/src/main/drivers/osd.h index a8b0bbc8e4..a69bc5b360 100644 --- a/src/main/drivers/osd.h +++ b/src/main/drivers/osd.h @@ -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 { diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 55714d059e..39305d77f3 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1578,11 +1578,11 @@ static void printGeozones(uint8_t dumpMask, const geoZoneConfig_t *geoZone, cons && geoZone[i].fenceAction == defaultGeoZone->fenceAction && geoZone[i].vertexCount == defaultGeoZone->vertexCount; - cliDefaultPrintLinef(dumpMask, equalsDefault, format, defaultGeoZone[i].shape, defaultGeoZone[i].type, defaultGeoZone[i].minAltitude, defaultGeoZone[i].maxAltitude, defaultGeoZone[i].isSealevelRef, defaultGeoZone[i].fenceAction, defaultGeoZone[i].vertexCount); + cliDefaultPrintLinef(dumpMask, equalsDefault, format, defaultGeoZone[i].shape, defaultGeoZone[i].type, defaultGeoZone[i].minAltitude, defaultGeoZone[i].maxAltitude, defaultGeoZone[i].isSealevelRef, defaultGeoZone[i].fenceAction, defaultGeoZone[i].vertexCount); } - cliDumpPrintLinef(dumpMask, equalsDefault, format, i, geoZone[i].shape, geoZone[i].type, geoZone[i].minAltitude, geoZone[i].maxAltitude, geoZone[i].isSealevelRef, geoZone[i].fenceAction, geoZone[i].vertexCount); + cliDumpPrintLinef(dumpMask, equalsDefault, format, i, geoZone[i].shape, geoZone[i].type, geoZone[i].minAltitude, geoZone[i].maxAltitude, geoZone[i].isSealevelRef, geoZone[i].fenceAction, geoZone[i].vertexCount); } -} +} static void printGeozoneVertices(uint8_t dumpMask, const vertexConfig_t *vertices, const vertexConfig_t *defaultVertices) { @@ -1594,11 +1594,11 @@ static void printGeozoneVertices(uint8_t dumpMask, const vertexConfig_t *vertice && vertices[i].lat == defaultVertices->lat && vertices[i].lon == defaultVertices->lon && vertices[i].zoneId == defaultVertices->zoneId; - + cliDefaultPrintLinef(dumpMask, equalsDefault, format, defaultVertices[i].zoneId, defaultVertices[i].idx, defaultVertices[i].lat, defaultVertices[i].lon); } - - cliDumpPrintLinef(dumpMask, equalsDefault, format, vertices[i].zoneId, vertices[i].idx, vertices[i].lat, vertices[i].lon); + + cliDumpPrintLinef(dumpMask, equalsDefault, format, vertices[i].zoneId, vertices[i].idx, vertices[i].lat, vertices[i].lon); } if (!defaultVertices) { @@ -1608,10 +1608,10 @@ static void printGeozoneVertices(uint8_t dumpMask, const vertexConfig_t *vertice } static void cliGeozone(char* cmdLine) -{ +{ if (isEmpty(cmdLine)) { printGeozones(DUMP_MASTER, geoZonesConfig(0), NULL); - } else if (sl_strcasecmp(cmdLine, "vertex") == 0) { + } else if (sl_strcasecmp(cmdLine, "vertex") == 0) { printGeozoneVertices(DUMP_MASTER, geoZoneVertices(0), NULL); } else if (sl_strncasecmp(cmdLine, "vertex reset", 12) == 0) { const char* ptr = &cmdLine[12]; @@ -1648,7 +1648,7 @@ static void cliGeozone(char* cmdLine) const char* ptr = cmdLine; uint8_t argumentCount = 1; - if ((ptr = nextArg(ptr))) { + if ((ptr = nextArg(ptr))) { zoneId = fastA2I(ptr); if (zoneId < 0) { return; @@ -1678,7 +1678,7 @@ static void cliGeozone(char* cmdLine) cliShowParseError(); return; } - + if ((ptr = nextArg(ptr))) { argumentCount++; lon = fastA2I(ptr); @@ -1695,7 +1695,7 @@ static void cliGeozone(char* cmdLine) cliShowParseError(); return; } - + for (uint8_t i = 0; i < MAX_VERTICES_IN_CONFIG; i++) { if (geoZoneVertices(i)->zoneId == zoneId && geoZoneVertices(i)->idx == vertexZoneIdx) { geoZoneVerticesMutable(i)->lat = lat; @@ -1719,8 +1719,8 @@ static void cliGeozone(char* cmdLine) geoZoneVerticesMutable(vertexIdx)->lat = lat; geoZoneVerticesMutable(vertexIdx)->lon = lon; geoZoneVerticesMutable(vertexIdx)->zoneId = zoneId; - geoZoneVerticesMutable(vertexIdx)->idx = vertexZoneIdx; - + geoZoneVerticesMutable(vertexIdx)->idx = vertexZoneIdx; + uint8_t totalVertices = geozoneGetUsedVerticesCount(); cliPrintLinef("# %u vertices free (Used %u of %u)", MAX_VERTICES_IN_CONFIG - totalVertices, totalVertices, MAX_VERTICES_IN_CONFIG); @@ -1733,7 +1733,7 @@ static void cliGeozone(char* cmdLine) } else { geozoneReset(-1); geozoneResetVertices(-1, -1); - } + } } else { int8_t idx = 0, isPolygon = 0, isInclusive = 0, fenceAction = 0, seaLevelRef = 0, vertexCount = 0; int32_t minAltitude = 0, maxAltitude = 0; @@ -1745,7 +1745,7 @@ static void cliGeozone(char* cmdLine) cliShowArgumentRangeError("geozone index", 0, MAX_GEOZONES_IN_CONFIG - 1); return; } - + if ((ptr = nextArg(ptr))) { argumentCount++; isPolygon = fastA2I(ptr); @@ -1787,7 +1787,7 @@ static void cliGeozone(char* cmdLine) } if ((ptr = nextArg(ptr))){ - argumentCount++; + argumentCount++; fenceAction = fastA2I(ptr); if (fenceAction < 0 || fenceAction > GEOFENCE_ACTION_RTH) { cliShowArgumentRangeError("fence action", 0, GEOFENCE_ACTION_RTH); @@ -1812,7 +1812,7 @@ static void cliGeozone(char* cmdLine) if ((ptr = nextArg(ptr))){ argumentCount++; - } + } if (argumentCount != 8) { cliShowParseError(); @@ -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) - cliPrintLinef(" %s", OSD_MSG_DISABLE_NAV_FIRST); - if (reason & NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR) + 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) cliPrintLinef(" FIRST WP TOO FAR"); } } diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a21d51d477..74afae23d9 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -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"] diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c index ca9f96848f..cb7a3a4976 100644 --- a/src/main/io/displayport_msp_osd.c +++ b/src/main/io/displayport_msp_osd.c @@ -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; diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index cd23edd6b3..811186d0bd 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -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; diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index 9e3c04d2c1..a793bdae2c 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -39,6 +39,7 @@ #include #include +#include #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); diff --git a/src/main/rx/jetiexbus.h b/src/main/rx/jetiexbus.h index d23999e9b0..5029cad7c3 100644 --- a/src/main/rx/jetiexbus.h +++ b/src/main/rx/jetiexbus.h @@ -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); diff --git a/src/main/target/MATEKF405/CMakeLists.txt b/src/main/target/MATEKF405/CMakeLists.txt index ebf457cda2..d5c4656763 100644 --- a/src/main/target/MATEKF405/CMakeLists.txt +++ b/src/main/target/MATEKF405/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f405xg(MATEKF405) target_stm32f405xg(MATEKF405OSD) +target_stm32f405xg(MATEKF405MINI) diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index 50786e8efc..a33807c06a 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -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 diff --git a/src/main/target/ORBITF435/CMakeLists.txt b/src/main/target/ORBITF435/CMakeLists.txt new file mode 100644 index 0000000000..6ffb8ec5a3 --- /dev/null +++ b/src/main/target/ORBITF435/CMakeLists.txt @@ -0,0 +1,2 @@ +target_at32f43x_xGT7(ORBITF435) +target_at32f43x_xGT7(ORBITF435_SD) \ No newline at end of file diff --git a/src/main/target/ORBITF435/config.c b/src/main/target/ORBITF435/config.c new file mode 100644 index 0000000000..e2ccf38659 --- /dev/null +++ b/src/main/target/ORBITF435/config.c @@ -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 +#include +#include + +#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 +} diff --git a/src/main/target/ORBITF435/target.c b/src/main/target/ORBITF435/target.c new file mode 100644 index 0000000000..25b5aae207 --- /dev/null +++ b/src/main/target/ORBITF435/target.c @@ -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 + +#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]); diff --git a/src/main/target/ORBITF435/target.h b/src/main/target/ORBITF435/target.h new file mode 100644 index 0000000000..99c54fecbb --- /dev/null +++ b/src/main/target/ORBITF435/target.h @@ -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)) \ No newline at end of file diff --git a/src/main/target/SKYSTARSF405WING/target.c b/src/main/target/SKYSTARSF405WING/target.c index 19260ea4b2..98f833aec7 100644 --- a/src/main/target/SKYSTARSF405WING/target.c +++ b/src/main/target/SKYSTARSF405WING/target.c @@ -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 diff --git a/src/main/target/SKYSTARSF405WING/target.h b/src/main/target/SKYSTARSF405WING/target.h index 2c219712ad..1eba71a1e4 100644 --- a/src/main/target/SKYSTARSF405WING/target.h +++ b/src/main/target/SKYSTARSF405WING/target.h @@ -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 diff --git a/src/main/target/TBS_LUCID_H7/target.c b/src/main/target/TBS_LUCID_H7/target.c index 30e16b8482..88b2df3e3b 100644 --- a/src/main/target/TBS_LUCID_H7/target.c +++ b/src/main/target/TBS_LUCID_H7/target.c @@ -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 diff --git a/src/main/target/TBS_LUCID_H7/target.h b/src/main/target/TBS_LUCID_H7/target.h index c215c4bef8..61953d0078 100644 --- a/src/main/target/TBS_LUCID_H7/target.h +++ b/src/main/target/TBS_LUCID_H7/target.h @@ -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 diff --git a/src/main/telemetry/jetiexbus.c b/src/main/telemetry/jetiexbus.c index b0ffad8434..56073e54cc 100644 --- a/src/main/telemetry/jetiexbus.c +++ b/src/main/telemetry/jetiexbus.c @@ -138,14 +138,22 @@ const exBusSensor_t jetiExSensors[] = { {"GPS Speed", "m/s", EX_TYPE_22b, DECIMAL_MASK(2)}, {"GPS H-Distance", "m", EX_TYPE_22b, DECIMAL_MASK(0)}, {"GPS H-Direction", "\xB0", EX_TYPE_22b, DECIMAL_MASK(1)}, - {"INAV D2", "", EX_TYPE_DES, 0 }, // device descripton + {"INAV D2", "", EX_TYPE_DES, 0 }, // device descripton {"GPS Heading", "\xB0", EX_TYPE_22b, DECIMAL_MASK(1)}, {"GPS Altitude", "m", EX_TYPE_22b, DECIMAL_MASK(2)}, {"G-Force X", "", EX_TYPE_22b, DECIMAL_MASK(3)}, {"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 } @@ -421,6 +447,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,13 +580,7 @@ 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; - } - } + 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; } diff --git a/src/main/telemetry/jetiexbus.h b/src/main/telemetry/jetiexbus.h index 9c8327db4a..3c6b465ed0 100644 --- a/src/main/telemetry/jetiexbus.h +++ b/src/main/telemetry/jetiexbus.h @@ -17,6 +17,8 @@ #pragma once +#define JETI_EXBUS_TELEMETRY_FRAME_LEN 128 + void initJetiExBusTelemetry(void); void checkJetiExBusTelemetryState(void); void handleJetiExBusTelemetry(void); diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 45ab37deec..2b56e646cf 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -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)