diff --git a/.github/no-response.yml b/.github/no-response.yml new file mode 100644 index 0000000000..8002aa3ad9 --- /dev/null +++ b/.github/no-response.yml @@ -0,0 +1,12 @@ +# Configuration for probot-no-response - https://github.com/probot/no-response + +# Number of days of inactivity before an Issue is closed for lack of response +daysUntilClose: 3 +# Label requiring a response +responseRequiredLabel: Missing Information +# Comment to post when closing an Issue for lack of response. Set to `false` to disable +closeComment: > + This issue has been automatically closed because the information we asked + to be provided when opening it was not supplied by the original author. + With only the information that is currently in the issue, we don't have + enough information to take action. \ No newline at end of file diff --git a/docs/Cli.md b/docs/Cli.md index eb6360a548..851f623f89 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -491,6 +491,7 @@ A shorter form is also supported to enable and disable functions using `serial < | vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | | vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. | | vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as it's capabilities | | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | | thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | diff --git a/docs/Logic Conditions.md b/docs/Logic Conditions.md index c04fa06353..97f24933bb 100644 --- a/docs/Logic Conditions.md +++ b/docs/Logic Conditions.md @@ -9,7 +9,7 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL ## CLI -`logic ` +`logic ` * `` - ID of Logic Condition rule * `` - `0` evaluates as disabled, `1` evaluates as enabled @@ -102,4 +102,4 @@ All flags are reseted on ARM and DISARM event. | bit | Decimal | Function | |---- |---- |---- | -| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted | \ No newline at end of file +| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted | diff --git a/docs/Navigation.md b/docs/Navigation.md index 1b31da1289..66970585a4 100755 --- a/docs/Navigation.md +++ b/docs/Navigation.md @@ -58,12 +58,14 @@ When deciding what altitude to maintain, RTH has 4 different modes of operation Parameters: - * `` - The action to be taken at the WP. The following are enumerations are available in inav 2.5 and later: + * `` - The action to be taken at the WP. The following are enumerations are available in inav 2.6 and later: * 0 - Unused / Unassigned * 1 - WAYPOINT * 3 - POSHOLD_TIME * 4 - RTH + * 5 - SET_POI * 6 - JUMP + * 7 - SET_HEAD * 8 - LAND * `` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789). @@ -72,7 +74,7 @@ Parameters: * `` - Altitude in cm. - * `` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). + * `` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI. * `` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP. diff --git a/docs/development/Generic_Linux_development.md b/docs/development/Generic_Linux_development.md index 5dc7812582..5e8a782249 100644 --- a/docs/development/Generic_Linux_development.md +++ b/docs/development/Generic_Linux_development.md @@ -24,16 +24,22 @@ In addition to a cross-compiler, it is necessary to install some other tools: ### Ubuntu / Debian ``` +$ # make sure the system is updated first +$ sudo apt update && sudo apt upgrade $ sudo apt install gcc git make ruby curl ``` ### Fedora ``` +$ # make sure the system is updated first +$ sudo dnf -y update $ sudo dnf install gcc git make ruby curl ``` ### Arch ``` +$ # make sure the system is updated first +$ sudo pacman -Syu $ sudo pacman -S gcc git make ruby curl ``` diff --git a/make/release.mk b/make/release.mk index f80fa989a2..0edda29c66 100644 --- a/make/release.mk +++ b/make/release.mk @@ -15,7 +15,9 @@ RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4 RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 +# MATEK targets RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX +RELEASE_TARGETS += MATEKF765 RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL @@ -27,10 +29,9 @@ RELEASE_TARGETS += OMNIBUSF4V6 RELEASE_TARGETS += MAMBAF405 MAMBAF405US MAMBAF722 -RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING +# IFLIGHT targets +RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD RELEASE_TARGETS += AIKONF4 -RELEASE_TARGETS += MATEKF765 - RELEASE_TARGETS += ZEEZF7 diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c new file mode 100644 index 0000000000..dcedfc373c --- /dev/null +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -0,0 +1,321 @@ +/* + * This file is part of INAV. + * + * 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/. + * + * Copyright: INAVFLIGHT OU + */ + +#include +#include +#include + +#include + +#include "build/build_config.h" +#include "build/debug.h" +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/bus.h" +#include "drivers/time.h" +#include "drivers/barometer/barometer.h" +#include "drivers/barometer/barometer_dps310.h" + +#if defined(USE_BARO) && defined(USE_BARO_DPS310) + +#define DPS310_REG_PSR_B2 0x00 +#define DPS310_REG_PSR_B1 0x01 +#define DPS310_REG_PSR_B0 0x02 +#define DPS310_REG_TMP_B2 0x03 +#define DPS310_REG_TMP_B1 0x04 +#define DPS310_REG_TMP_B0 0x05 +#define DPS310_REG_PRS_CFG 0x06 +#define DPS310_REG_TMP_CFG 0x07 +#define DPS310_REG_MEAS_CFG 0x08 +#define DPS310_REG_CFG_REG 0x09 + +#define DPS310_REG_RESET 0x0C +#define DPS310_REG_ID 0x0D + +#define DPS310_REG_COEF 0x10 +#define DPS310_REG_COEF_SRCE 0x28 + + +#define DPS310_ID_REV_AND_PROD_ID (0x10) + +#define DPS310_RESET_BIT_SOFT_RST (0x09) // 0b1001 + +#define DPS310_MEAS_CFG_COEF_RDY (1 << 7) +#define DPS310_MEAS_CFG_SENSOR_RDY (1 << 6) +#define DPS310_MEAS_CFG_TMP_RDY (1 << 5) +#define DPS310_MEAS_CFG_PRS_RDY (1 << 4) +#define DPS310_MEAS_CFG_MEAS_CTRL_CONT (0x7) + +#define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. +#define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). + +#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) // +#define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. +#define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard). + +#define DPS310_CFG_REG_BIT_P_SHIFT (0x04) +#define DPS310_CFG_REG_BIT_T_SHIFT (0x08) + +#define DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE (0x80) + +typedef struct { + int16_t c0; // 12bit + int16_t c1; // 12bit + int32_t c00; // 20bit + int32_t c10; // 20bit + int16_t c01; // 16bit + int16_t c11; // 16bit + int16_t c20; // 16bit + int16_t c21; // 16bit + int16_t c30; // 16bit +} calibrationCoefficients_t; + +typedef struct { + calibrationCoefficients_t calib; + float pressure; // Pa + float temperature; // DegC +} baroState_t; + +static baroState_t baroState; + + +// Helper functions +static uint8_t registerRead(busDevice_t * busDev, uint8_t reg) +{ + uint8_t buf; + busRead(busDev, reg, &buf); + return buf; +} + +static void registerWrite(busDevice_t * busDev, uint8_t reg, uint8_t value) +{ + busWrite(busDev, reg, value); +} + +static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +{ + uint8_t val = registerRead(busDev, reg); + + if ((val & setbits) != setbits) { + val |= setbits; + registerWrite(busDev, reg, val); + } +} + +static int32_t getTwosComplement(uint32_t raw, uint8_t length) +{ + if (raw & ((int)1 << (length - 1))) { + return ((int32_t)raw) - ((int32_t)1 << length); + } + else { + return raw; + } +} + +static bool deviceConfigure(busDevice_t * busDev) +{ + // Trigger a chip reset + registerSetBits(busDev, DPS310_REG_RESET, DPS310_RESET_BIT_SOFT_RST); + + // Sleep 40ms + delay(40); + + uint8_t status = registerRead(busDev, DPS310_REG_MEAS_CFG); + + // Check if coefficients are available + if ((status & DPS310_MEAS_CFG_COEF_RDY) == 0) { + return false; + } + + // Check if sensor initialization is complete + if ((status & DPS310_MEAS_CFG_SENSOR_RDY) == 0) { + return false; + } + + // 1. Read the pressure calibration coefficients (c00, c10, c20, c30, c01, c11, and c21) from the Calibration Coefficient register. + // Note: The coefficients read from the coefficient register are 2's complement numbers. + uint8_t coef[18]; + if (!busReadBuf(busDev, DPS310_REG_COEF, coef, sizeof(coef))) { + return false; + } + + // 0x11 c0 [3:0] + 0x10 c0 [11:4] + baroState.calib.c0 = getTwosComplement(((uint32_t)coef[0] << 4) | (((uint32_t)coef[1] >> 4) & 0x0F), 12); + + // 0x11 c1 [11:8] + 0x12 c1 [7:0] + baroState.calib.c1 = getTwosComplement((((uint32_t)coef[1] & 0x0F) << 8) | (uint32_t)coef[2], 12); + + // 0x13 c00 [19:12] + 0x14 c00 [11:4] + 0x15 c00 [3:0] + baroState.calib.c00 = getTwosComplement(((uint32_t)coef[3] << 12) | ((uint32_t)coef[4] << 4) | (((uint32_t)coef[5] >> 4) & 0x0F), 20); + + // 0x15 c10 [19:16] + 0x16 c10 [15:8] + 0x17 c10 [7:0] + baroState.calib.c10 = getTwosComplement((((uint32_t)coef[5] & 0x0F) << 16) | ((uint32_t)coef[6] << 8) | (uint32_t)coef[7], 20); + + // 0x18 c01 [15:8] + 0x19 c01 [7:0] + baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); + + // 0x1A c11 [15:8] + 0x1B c11 [7:0] + baroState.calib.c11 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); + + // 0x1C c20 [15:8] + 0x1D c20 [7:0] + baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16); + + // 0x1E c21 [15:8] + 0x1F c21 [7:0] + baroState.calib.c21 = getTwosComplement(((uint32_t)coef[14] << 8) | (uint32_t)coef[15], 16); + + // 0x20 c30 [15:8] + 0x21 c30 [7:0] + baroState.calib.c30 = getTwosComplement(((uint32_t)coef[16] << 8) | (uint32_t)coef[17], 16); + + // PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard) + registerSetBits(busDev, DPS310_REG_PRS_CFG, DPS310_PRS_CFG_BIT_PM_RATE_32HZ | DPS310_PRS_CFG_BIT_PM_PRC_16); + + // TMP_CFG: temperature measurement rate (32 Hz) and oversampling (16 times) + const uint8_t TMP_COEF_SRCE = registerRead(busDev, DPS310_REG_COEF_SRCE) & DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE; + registerSetBits(busDev, DPS310_REG_TMP_CFG, DPS310_TMP_CFG_BIT_TMP_RATE_32HZ | DPS310_TMP_CFG_BIT_TMP_PRC_16 | TMP_COEF_SRCE); + + // CFG_REG: set pressure and temperature result bit-shift (required when the oversampling rate is >8 times) + registerSetBits(busDev, DPS310_REG_CFG_REG, DPS310_CFG_REG_BIT_T_SHIFT | DPS310_CFG_REG_BIT_P_SHIFT); + + // MEAS_CFG: Continuous pressure and temperature measurement + registerSetBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_CONT); + + return true; +} + +static bool deviceReadMeasurement(baroDev_t *baro) +{ + // 1. Check if pressure is ready + bool pressure_ready = registerRead(baro->busDev, DPS310_REG_MEAS_CFG) & DPS310_MEAS_CFG_PRS_RDY; + if (!pressure_ready) { + return false; + } + + // 2. Choose scaling factors kT (for temperature) and kP (for pressure) based on the chosen precision rate. + // The scaling factors are listed in Table 9. + static float kT = 253952; // 16 times (Standard) + static float kP = 253952; // 16 times (Standard) + + // 3. Read the pressure and temperature result from the registers + // Read PSR_B2, PSR_B1, PSR_B0, TMP_B2, TMP_B1, TMP_B0 + uint8_t buf[6]; + if (!busReadBuf(baro->busDev, DPS310_REG_PSR_B2, buf, 6)) { + return false; + } + + const int32_t Praw = getTwosComplement((buf[0] << 16) + (buf[1] << 8) + buf[2], 24); + const int32_t Traw = getTwosComplement((buf[3] << 16) + (buf[4] << 8) + buf[5], 24); + + // 4. Calculate scaled measurement results. + const float Praw_sc = Praw / kP; + const float Traw_sc = Traw / kT; + + // 5. Calculate compensated measurement results. + const float c00 = baroState.calib.c00; + const float c01 = baroState.calib.c01; + const float c10 = baroState.calib.c10; + const float c11 = baroState.calib.c11; + const float c20 = baroState.calib.c20; + const float c21 = baroState.calib.c21; + const float c30 = baroState.calib.c30; + + const float c0 = baroState.calib.c0; + const float c1 = baroState.calib.c1; + + baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21); + baroState.temperature = c0 * 0.5f + c1 * Traw_sc; + + return true; +} + +static bool deviceCalculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature) +{ + UNUSED(baro); + + if (pressure) { + *pressure = baroState.pressure; + } + + if (temperature) { + *temperature = (baroState.temperature * 100); // to centidegrees + } + + return true; +} + + + +#define DETECTION_MAX_RETRY_COUNT 5 +static bool deviceDetect(busDevice_t * busDev) +{ + for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) { + uint8_t chipId[1]; + + delay(100); + + bool ack = busReadBuf(busDev, DPS310_REG_ID, chipId, 1); + + if (ack && chipId[0] == DPS310_ID_REV_AND_PROD_ID) { + return true; + } + }; + + return false; +} + +bool baroDPS310Detect(baroDev_t *baro) +{ + baro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_DPS310, 0, OWNER_BARO); + if (baro->busDev == NULL) { + return false; + } + + if (!deviceDetect(baro->busDev)) { + busDeviceDeInit(baro->busDev); + return false; + } + + if (!deviceConfigure(baro->busDev)) { + busDeviceDeInit(baro->busDev); + return false; + } + + const uint32_t baroDelay = 1000000 / 32 / 2; // twice the sample rate to capture all new data + + baro->ut_delay = 0; + baro->start_ut = NULL; + baro->get_ut = NULL; + + baro->up_delay = baroDelay; + baro->start_up = NULL; + baro->get_up = deviceReadMeasurement; + + baro->calculate = deviceCalculate; + + return true; +} + +#endif diff --git a/src/main/drivers/barometer/barometer_dps310.h b/src/main/drivers/barometer/barometer_dps310.h new file mode 100644 index 0000000000..314c282c5c --- /dev/null +++ b/src/main/drivers/barometer/barometer_dps310.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV. + * + * 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/. + * + * Copyright: INAVFLIGHT OU + */ + +#pragma once + +bool baroDPS310Detect(baroDev_t *baro); diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index 7f7d06d092..d5a877f7d6 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -104,6 +104,7 @@ typedef enum { DEVHW_LPS25H, DEVHW_SPL06, DEVHW_BMP388, + DEVHW_DPS310, /* Compass chips */ DEVHW_HMC5883, diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 41dc46a02e..dc6f43f071 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1338,7 +1338,7 @@ static void cliWaypoints(char *cmdline) } else if (sl_strcasecmp(cmdline, "save") == 0) { posControl.waypointListValid = false; for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) { - if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND)) break; + if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND || posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD)) break; if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) { posControl.waypointCount = i + 1; posControl.waypointListValid = true; @@ -1933,9 +1933,9 @@ static void cliGvar(char *cmdline) { int32_t i = args[INDEX]; if ( i >= 0 && i < MAX_GLOBAL_VARIABLES && - args[DEFAULT] >= INT32_MIN && args[DEFAULT] <= INT32_MAX && - args[MIN] >= INT32_MIN && args[MIN] <= INT32_MAX && - args[MAX] >= INT32_MIN && args[MAX] <= INT32_MAX + args[DEFAULT] >= INT32_MIN && args[DEFAULT] <= INT32_MAX && + args[MIN] >= INT32_MIN && args[MIN] <= INT32_MAX && + args[MAX] >= INT32_MIN && args[MAX] <= INT32_MAX ) { globalVariableConfigsMutable(i)->defaultValue = args[DEFAULT]; globalVariableConfigsMutable(i)->min = args[MIN]; diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 6f7f0b9b6e..ac4656bcac 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -275,12 +275,6 @@ void init(void) // to run after the sensors have been detected. mspSerialInit(); -#ifdef USE_ESC_SENSOR - // DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization - // We may, however, do listen_only, so need to init this anyway - escSensorInitialize(); -#endif - #if defined(USE_DJI_HD_OSD) // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task djiOsdSerialInit(); @@ -320,6 +314,13 @@ void init(void) systemState |= SYSTEM_STATE_MOTORS_READY; +#ifdef USE_ESC_SENSOR + // DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization + // We may, however, do listen_only, so need to init this anyway + // Initialize escSensor after having done it with outputs + escSensorInitialize(); +#endif + #ifdef BEEPER beeperDevConfig_t beeperDevConfig = { .ioTag = IO_TAG(BEEPER), diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b346c9b05b..f1f6e3aa74 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -16,7 +16,7 @@ tables: values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"] enum: opticalFlowSensor_e - name: baro_hardware - values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"] + values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "FAKE"] enum: baroSensor_e - name: pitot_hardware values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"] @@ -2145,6 +2145,10 @@ groups: field: pitModeChan min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL + - name: vtx_max_power_override + field: maxPowerOverride + min: 0 + max: 10000 - name: PG_PINIOBOX_CONFIG type: pinioBoxConfig_t diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 972162264c..f4b999a534 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -43,7 +43,7 @@ #include "io/vtx_string.h" #include "io/vtx_control.h" -PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 2); PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, .band = VTX_SETTINGS_DEFAULT_BAND, @@ -51,6 +51,7 @@ PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, .power = VTX_SETTINGS_DEFAULT_POWER, .pitModeChan = VTX_SETTINGS_DEFAULT_PITMODE_CHANNEL, .lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF, + .maxPowerOverride = 0, ); typedef enum { @@ -86,29 +87,30 @@ static vtxSettingsConfig_t * vtxGetRuntimeSettings(void) static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings) { + uint8_t vtxBand; + uint8_t vtxChan; + // Shortcut for undefined band if (!runtimeSettings->band) { return false; } - if(!ARMING_FLAG(ARMED) && runtimeSettings->band) { - uint8_t vtxBand; - uint8_t vtxChan; - if (!vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) { - return false; - } - - if (vtxBand != runtimeSettings->band || vtxChan != runtimeSettings->channel) { - vtxCommonSetBandAndChannel(vtxDevice, runtimeSettings->band, runtimeSettings->channel); - return true; - } + if (!vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) { + return false; } + + if (vtxBand != runtimeSettings->band || vtxChan != runtimeSettings->channel) { + vtxCommonSetBandAndChannel(vtxDevice, runtimeSettings->band, runtimeSettings->channel); + return true; + } + return false; } static bool vtxProcessPower(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings) { uint8_t vtxPower; + if (!vtxCommonGetPowerIndex(vtxDevice, &vtxPower)) { return false; } @@ -117,6 +119,7 @@ static bool vtxProcessPower(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * vtxCommonSetPowerByIndex(vtxDevice, runtimeSettings->power); return true; } + return false; } @@ -129,25 +132,28 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t bool currPmSwitchState = false; static bool prevPmSwitchState = false; - if (!ARMING_FLAG(ARMED) && vtxCommonGetPitMode(vtxDevice, &pitOnOff)) { - if (currPmSwitchState != prevPmSwitchState) { - prevPmSwitchState = currPmSwitchState; + if (!vtxCommonGetPitMode(vtxDevice, &pitOnOff)) { + return false; + } - if (currPmSwitchState) { - if (0) { - if (!pitOnOff) { - vtxCommonSetPitMode(vtxDevice, true); - return true; - } - } - } else { - if (pitOnOff) { - vtxCommonSetPitMode(vtxDevice, false); + if (currPmSwitchState != prevPmSwitchState) { + prevPmSwitchState = currPmSwitchState; + + if (currPmSwitchState) { + if (0) { + if (!pitOnOff) { + vtxCommonSetPitMode(vtxDevice, true); return true; } } + } else { + if (pitOnOff) { + vtxCommonSetPitMode(vtxDevice, false); + return true; + } } } + return false; } @@ -167,25 +173,21 @@ void vtxUpdate(timeUs_t currentTimeUs) // Build runtime settings const vtxSettingsConfig_t * runtimeSettings = vtxGetRuntimeSettings(); - bool vtxUpdatePending = false; - switch (currentSchedule) { case VTX_PARAM_POWER: - vtxUpdatePending = vtxProcessPower(vtxDevice, runtimeSettings); + vtxProcessPower(vtxDevice, runtimeSettings); break; case VTX_PARAM_BANDCHAN: - vtxUpdatePending = vtxProcessBandAndChannel(vtxDevice, runtimeSettings); + vtxProcessBandAndChannel(vtxDevice, runtimeSettings); break; case VTX_PARAM_PITMODE: - vtxUpdatePending = vtxProcessPitMode(vtxDevice, runtimeSettings); + vtxProcessPitMode(vtxDevice, runtimeSettings); break; default: break; } - if (!ARMING_FLAG(ARMED) || vtxUpdatePending) { - vtxCommonProcess(vtxDevice, currentTimeUs); - } + vtxCommonProcess(vtxDevice, currentTimeUs); currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT; } diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index e3bb6018a6..4bff70af54 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -35,11 +35,12 @@ typedef enum { } vtxLowerPowerDisarm_e; typedef struct vtxSettingsConfig_s { - uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande - uint8_t channel; // 1-8 - uint8_t power; // 0 = lowest - uint16_t pitModeChan; // sets out-of-range pitmode frequency - uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e + uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande + uint8_t channel; // 1-8 + uint8_t power; // 0 = lowest + uint16_t pitModeChan; // sets out-of-range pitmode frequency + uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e + uint16_t maxPowerOverride; // for VTX drivers that are polling VTX capabilities - override what VTX is reporting } vtxSettingsConfig_t; PG_DECLARE(vtxSettingsConfig_t, vtxSettingsConfig); diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 3e95ac1ae8..4e22d35f2f 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -228,9 +228,17 @@ static vtxProtoResponseType_e vtxProtoProcessResponse(void) vtxState.capabilities.freqMin = vtxState.recvPkt[2] | (vtxState.recvPkt[3] << 8); vtxState.capabilities.freqMax = vtxState.recvPkt[4] | (vtxState.recvPkt[5] << 8); vtxState.capabilities.powerMax = vtxState.recvPkt[6] | (vtxState.recvPkt[7] << 8); + if (vtxState.capabilities.freqMin != 0 && vtxState.capabilities.freqMin < vtxState.capabilities.freqMax) { - // Update max power metadata so OSD settings would match VTX capabiolities + // Some TRAMP VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX) + // Make use of vtxSettingsConfig()->maxPowerOverride to override + if (vtxSettingsConfig()->maxPowerOverride != 0) { + vtxState.capabilities.powerMax = vtxSettingsConfig()->maxPowerOverride; + } + + // Update max power metadata so OSD settings would match VTX capabilities vtxProtoUpdatePowerMetadata(vtxState.capabilities.powerMax); + return VTX_RESPONSE_TYPE_CAPABILITIES; } break; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 86855887c0..63b5f35f95 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -172,8 +172,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, } ); -EXTENDED_FASTRAM navigationPosControl_t posControl; -EXTENDED_FASTRAM navSystemStatus_t NAV_Status; +static navWapointHeading_t wpHeadingControl; +navigationPosControl_t posControl; +navSystemStatus_t NAV_Status; EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients; #if defined(NAV_BLACKBOX) @@ -209,6 +210,8 @@ void calculateInitialHoldPosition(fpVector3_t * pos); void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t yaw, int32_t distance); void calculateNewCruiseTarget(fpVector3_t * origin, int32_t yaw, int32_t distance); static bool isWaypointPositionReached(const fpVector3_t * pos, const bool isWaypointHome); +static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint_t * waypoint); +static navigationFSMEvent_t nextForNonGeoStates(void); void initializeRTHSanityChecker(const fpVector3_t * pos); bool validateRTHSanityChecker(void); @@ -1416,6 +1419,21 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_INITIALIZE(nav } } +static navigationFSMEvent_t nextForNonGeoStates(void) +{ + /* simple helper for non-geographical states that just set other data */ + const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) || (posControl.activeWaypointIndex >= (posControl.waypointCount - 1)); + + if (isLastWaypoint) { + // non-geo state is the last waypoint, switch to finish. + return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; + } else { + // Finished non-geo, move to next WP + posControl.activeWaypointIndex++; + return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP + } +} + static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(navigationFSMState_t previousState) { /* A helper function to do waypoint-specific action */ @@ -1435,28 +1453,36 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav if(posControl.waypointList[posControl.activeWaypointIndex].p3 != -1){ if(posControl.waypointList[posControl.activeWaypointIndex].p3 == 0){ resetJumpCounter(); - const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) || - (posControl.activeWaypointIndex >= (posControl.waypointCount - 1)); - - if (isLastWaypoint) { - // JUMP is the last waypoint and we reached the last jump, switch to finish. - return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; - } else { - // Finished JUMP, move to next WP - posControl.activeWaypointIndex++; - return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP - } + return nextForNonGeoStates(); } else { posControl.waypointList[posControl.activeWaypointIndex].p3--; } } - posControl.activeWaypointIndex = posControl.waypointList[posControl.activeWaypointIndex].p1; - return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP + case NAV_WP_ACTION_SET_POI: + if (STATE(MULTIROTOR)) { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_POI; + mapWaypointToLocalPosition(&wpHeadingControl.poi_pos, + &posControl.waypointList[posControl.activeWaypointIndex]); + } + return nextForNonGeoStates(); + + case NAV_WP_ACTION_SET_HEAD: + if (STATE(MULTIROTOR)) { + if (posControl.waypointList[posControl.activeWaypointIndex].p1 < 0 || + posControl.waypointList[posControl.activeWaypointIndex].p1 > 359) { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_NONE; + } else { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_FIXED; + wpHeadingControl.heading = DEGREES_TO_CENTIDEGREES(posControl.waypointList[posControl.activeWaypointIndex].p1); + } + } + return nextForNonGeoStates(); + case NAV_WP_ACTION_RTH: posControl.rthState.rthInitialDistance = posControl.homeDistance; initializeRTHSanityChecker(&navGetCurrentActualPositionAndVelocity()->pos); @@ -1488,11 +1514,25 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na posControl.wpInitialDistance, posControl.wpInitialDistance / 10.0f, posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z); setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING); + if(STATE(MULTIROTOR)) { + switch (wpHeadingControl.mode) { + case NAV_WP_HEAD_MODE_NONE: + break; + case NAV_WP_HEAD_MODE_FIXED: + setDesiredPosition(NULL, wpHeadingControl.heading, NAV_POS_UPDATE_HEADING); + break; + case NAV_WP_HEAD_MODE_POI: + setDesiredPosition(&wpHeadingControl.poi_pos, 0, NAV_POS_UPDATE_BEARING); + break; + } + } return NAV_FSM_EVENT_NONE; // will re-process state in >10ms } break; case NAV_WP_ACTION_JUMP: + case NAV_WP_ACTION_SET_HEAD: + case NAV_WP_ACTION_SET_POI: UNREACHABLE(); case NAV_WP_ACTION_RTH: @@ -1530,6 +1570,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_REACHED(naviga return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_WAYPOINT_NEXT case NAV_WP_ACTION_JUMP: + case NAV_WP_ACTION_SET_HEAD: + case NAV_WP_ACTION_SET_POI: UNREACHABLE(); case NAV_WP_ACTION_RTH: @@ -2765,7 +2807,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) } // WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) { - if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND) { + if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) { posControl.waypointList[wpNumber - 1] = *wpData; diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 57927b0687..6ae9950603 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -237,10 +237,18 @@ typedef enum { NAV_WP_ACTION_WAYPOINT = 0x01, NAV_WP_ACTION_HOLD_TIME = 0x03, NAV_WP_ACTION_RTH = 0x04, + NAV_WP_ACTION_SET_POI = 0x05, NAV_WP_ACTION_JUMP = 0x06, + NAV_WP_ACTION_SET_HEAD = 0x07, NAV_WP_ACTION_LAND = 0x08 } navWaypointActions_e; +typedef enum { + NAV_WP_HEAD_MODE_NONE = 0, + NAV_WP_HEAD_MODE_POI = 1, + NAV_WP_HEAD_MODE_FIXED = 2 +} navWaypointHeadings_e; + typedef enum { NAV_WP_FLAG_LAST = 0xA5 } navWaypointFlags_e; @@ -254,6 +262,12 @@ typedef struct { uint8_t flag; } navWaypoint_t; +typedef struct { + navWaypointHeadings_e mode; + uint32_t heading; // fixed heading * 100 (SET_HEAD) + fpVector3_t poi_pos; // POI location in local coordinates (SET_POI) +} navWapointHeading_t; + typedef struct radar_pois_s { gpsLocation_t gps; uint8_t state; diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index f9e72f15a8..567264f783 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -38,6 +38,7 @@ #include "drivers/barometer/barometer_fake.h" #include "drivers/barometer/barometer_ms56xx.h" #include "drivers/barometer/barometer_spl06.h" +#include "drivers/barometer/barometer_dps310.h" #include "drivers/time.h" #include "fc/runtime_config.h" @@ -172,6 +173,19 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse) } FALLTHROUGH; + case BARO_DPS310: +#if defined(USE_BARO_DPS310) + if (baroDPS310Detect(dev)) { + baroHardware = BARO_DPS310; + break; + } +#endif + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (baroHardwareToUse != BARO_AUTODETECT) { + break; + } + FALLTHROUGH; + case BARO_FAKE: #ifdef USE_FAKE_BARO if (fakeBaroDetect(dev)) { @@ -265,15 +279,23 @@ uint32_t baroUpdate(void) switch (state) { default: case BAROMETER_NEEDS_SAMPLES: - baro.dev.get_ut(&baro.dev); - baro.dev.start_up(&baro.dev); + if (baro.dev.get_ut) { + baro.dev.get_ut(&baro.dev); + } + if (baro.dev.start_up) { + baro.dev.start_up(&baro.dev); + } state = BAROMETER_NEEDS_CALCULATION; return baro.dev.up_delay; break; case BAROMETER_NEEDS_CALCULATION: - baro.dev.get_up(&baro.dev); - baro.dev.start_ut(&baro.dev); + if (baro.dev.get_up) { + baro.dev.get_up(&baro.dev); + } + if (baro.dev.start_ut) { + baro.dev.start_ut(&baro.dev); + } baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); if (barometerConfig()->use_median_filtering) { baro.baroPressure = applyBarometerMedianFilter(baro.baroPressure); diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index 3e10700f0c..6301c79b0b 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -29,9 +29,10 @@ typedef enum { BARO_BMP280 = 4, BARO_MS5607 = 5, BARO_LPS25H = 6, - BARO_SPL06 = 7, + BARO_SPL06 = 7, BARO_BMP388 = 8, - BARO_FAKE = 9, + BARO_DPS310 = 9, + BARO_FAKE = 10, BARO_MAX = BARO_FAKE } baroSensor_e; diff --git a/src/main/target/FIREWORKSV2/target.h b/src/main/target/FIREWORKSV2/target.h index b8dd5c6ef6..c3818458fd 100644 --- a/src/main/target/FIREWORKSV2/target.h +++ b/src/main/target/FIREWORKSV2/target.h @@ -75,13 +75,14 @@ # define IMU_2_SPI_BUS BUS_SPI1 # define IMU_2_ALIGN CW0_DEG #else - // FIREWORKS V2 -# define IMU_1_CS_PIN PD2 -# define IMU_1_SPI_BUS BUS_SPI3 -# define IMU_1_ALIGN CW180_DEG -# define IMU_2_CS_PIN PA4 -# define IMU_2_SPI_BUS BUS_SPI1 -# define IMU_2_ALIGN CW0_DEG_FLIP + // IMU_1 is verified to work on OBF4V6 and Omnibus Fireworks board +# define IMU_1_CS_PIN PA4 +# define IMU_1_SPI_BUS BUS_SPI1 +# define IMU_1_ALIGN CW0_DEG_FLIP + // IMU_2 is sketchy and was not verified on actual hardware +# define IMU_2_CS_PIN PD2 +# define IMU_2_SPI_BUS BUS_SPI3 +# define IMU_2_ALIGN CW180_DEG #endif #define USE_MAG diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index c4603911cb..c445959610 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -120,6 +120,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/FURYF4OSD/target.mk b/src/main/target/FURYF4OSD/target.mk index 0b76bb0235..272b981bb7 100644 --- a/src/main/target/FURYF4OSD/target.mk +++ b/src/main/target/FURYF4OSD/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.c b/src/main/target/IFLIGHTF4_SUCCEXD/target.c new file mode 100644 index 0000000000..142812dd39 --- /dev/null +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.c @@ -0,0 +1,37 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include +#include +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h new file mode 100644 index 0000000000..e47b9c7638 --- /dev/null +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.h @@ -0,0 +1,148 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "IFSD" +#define USBD_PRODUCT_STRING "IFLIGHT_SucceX_D" + +#define LED0 PC13 +#define LED1 PC14 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ********************** +#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_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_EXTI +#define GYRO_INT_EXTI PA1 +#define USE_MPU_DATA_READY_SIGNAL + +// *************** SPI2 OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI3 FLASH ************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define M25P16_CS_PIN PA15 +#define M25P16_SPI_BUS BUS_SPI3 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PC15 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define SERIAL_PORT_COUNT 3 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** I2C /Baro/Mag/Pitot ******************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8975 + +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_RANGEFINDER_HCSR04_I2C +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#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 (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 4 diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.mk b/src/main/target/IFLIGHTF4_SUCCEXD/target.mk new file mode 100644 index 0000000000..ff3c58d4a0 --- /dev/null +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.mk @@ -0,0 +1,17 @@ +F411_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/compass/compass_ak8975.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c diff --git a/src/main/target/IFLIGHTF4_TWING/target.h b/src/main/target/IFLIGHTF4_TWING/target.h index 27d99bdcf7..cbb9d29428 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.h +++ b/src/main/target/IFLIGHTF4_TWING/target.h @@ -60,6 +60,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHTF4_TWING/target.mk b/src/main/target/IFLIGHTF4_TWING/target.mk index 8979319492..b4c202b347 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.mk +++ b/src/main/target/IFLIGHTF4_TWING/target.mk @@ -5,6 +5,7 @@ FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index a6a9e63de2..bac28ceea0 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -63,6 +63,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C2 #define USE_BARO_BMP280 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/IFLIGHTF7_TWING/target.mk b/src/main/target/IFLIGHTF7_TWING/target.mk index 57bc66e9e8..77545402ae 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.mk +++ b/src/main/target/IFLIGHTF7_TWING/target.mk @@ -4,6 +4,7 @@ FEATURES += ONBOARDFLASH VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index 077155b1ff..37e7f78096 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -147,6 +147,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk index dd5ce7864a..62dd163f0c 100755 --- a/src/main/target/MATEKF405/target.mk +++ b/src/main/target/MATEKF405/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 513b14a8b2..81681b94f5 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -58,6 +58,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/MATEKF405SE/target.mk b/src/main/target/MATEKF405SE/target.mk index 8a0cc40ea7..13886f855e 100644 --- a/src/main/target/MATEKF405SE/target.mk +++ b/src/main/target/MATEKF405SE/target.mk @@ -6,6 +6,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index 7063d18c38..967e3c0ef8 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -118,6 +118,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411/target.mk b/src/main/target/MATEKF411/target.mk index f383248f31..1ea03d20db 100755 --- a/src/main/target/MATEKF411/target.mk +++ b/src/main/target/MATEKF411/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index cbffcd1a2c..790be95bac 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -95,6 +95,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411SE/target.mk b/src/main/target/MATEKF411SE/target.mk index ee090ce48f..9481999868 100755 --- a/src/main/target/MATEKF411SE/target.mk +++ b/src/main/target/MATEKF411SE/target.mk @@ -6,6 +6,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 62227998e8..a99a60afc1 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -56,6 +56,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk index f221bb51ca..a62d66f532 100755 --- a/src/main/target/MATEKF722/target.mk +++ b/src/main/target/MATEKF722/target.mk @@ -5,6 +5,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/barometer/barometer_ms56xx.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index 38e9a8f380..f2f1bca242 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -53,6 +53,7 @@ #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722PX/target.mk b/src/main/target/MATEKF722PX/target.mk index 0db5e55e78..3b7c3615dd 100755 --- a/src/main/target/MATEKF722PX/target.mk +++ b/src/main/target/MATEKF722PX/target.mk @@ -5,6 +5,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 56dcdcc886..7942a30e21 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -70,6 +70,7 @@ #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722SE/target.mk b/src/main/target/MATEKF722SE/target.mk index 63b91d3000..19ae98915c 100644 --- a/src/main/target/MATEKF722SE/target.mk +++ b/src/main/target/MATEKF722SE/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index fcddab2693..8fefd8d077 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -74,6 +74,7 @@ #define BARO_I2C_BUS BUS_I2C2 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF765/target.mk b/src/main/target/MATEKF765/target.mk index 11d75e59b3..9e34a0864e 100644 --- a/src/main/target/MATEKF765/target.mk +++ b/src/main/target/MATEKF765/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 1e35d2baef..b372e9c8f7 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -149,6 +149,18 @@ #endif #endif +#if defined(USE_BARO_DPS310) + #if defined(DPS310_SPI_BUS) + BUSDEV_REGISTER_SPI(busdev_dps310, DEVHW_DPS310, DPS310_SPI_BUS, DPS310_CS_PIN, NONE, DEVFLAGS_NONE, 0); + #elif defined(DPS310_I2C_BUS) || defined(BARO_I2C_BUS) + #if !defined(DPS310_I2C_BUS) + #define DPS310_I2C_BUS BARO_I2C_BUS + #endif + BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE, 0); + #endif +#endif + + /** COMPASS SENSORS **/ #if !defined(USE_TARGET_MAG_HARDWARE_DESCRIPTORS) #if defined(USE_MAG_HMC5883)