Skip to content

Commit

Permalink
Merge branch 'release_7.1.0' into custom-23
Browse files Browse the repository at this point in the history
  • Loading branch information
breadoven committed Mar 5, 2024
2 parents a5b796b + 6f2b6ee commit d7bb6e1
Show file tree
Hide file tree
Showing 16 changed files with 525 additions and 30 deletions.
11 changes: 9 additions & 2 deletions docs/SITL/RealFlight.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,15 @@
Supported are RealFlight 9.5S and RealFlight Evolution, NOT RealFlight-X.

RealFlight is very well suited to simulate the model flight specific aspects. Autolaunch and the mixers can be used.
However, since the sceneries do not correspond to a real environment, the GPS data must be "faked". The position is always shown somewhere in southern Nevada ;).
GPS data and flight modes work fine though, only for missions with waypoints it is of course not ideal.

The RealFlight 3D sceneries are based on real topographic data of the Sierra Nevada in Southern Spain.
INAV uses as reference the scenery "RealFlight Ranch" which is located at the coordinates Lat: 37.118949°, Lon: -2.772960.
Use these scenery to use the mission planner and other GPS features.

> [!CAUTION]:
> The immediate surroundings of the airfield have been levelled in the scenery. If, for example, Autoland is to be tested here, do not use "Sea level ref" and the automatically determined heights of the Configurator.
> Either use relarive elevations or correct the elevation manually.
> The altitude of the airfield is exactly 1300 metres.
## Joystick
In the settings, calibrate the joystick, set it up and assign the axes in the same order as in INAV.
Expand Down
6 changes: 3 additions & 3 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -1948,7 +1948,7 @@ Weight of barometer measurements in estimated altitude and climb rate. Setting i

| Default | Min | Max |
| --- | --- | --- |
| 0.4 | 0 | 10 |
| 0.35 | 0 | 10 |

---

Expand All @@ -1958,7 +1958,7 @@ Weight of GPS altitude measurements in estimated altitude. Setting is used on bo

| Default | Min | Max |
| --- | --- | --- |
| 0.4 | 0 | 10 |
| 0.2 | 0 | 10 |

---

Expand All @@ -1968,7 +1968,7 @@ Weight of GPS climb rate measurements in estimated climb rate. Setting is used o

| Default | Min | Max |
| --- | --- | --- |
| 0.8 | 0 | 10 |
| 0.1 | 0 | 10 |

---

Expand Down
6 changes: 3 additions & 3 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2377,19 +2377,19 @@ groups:
field: w_z_baro_p
min: 0
max: 10
default_value: 0.4
default_value: 0.35
- name: inav_w_z_gps_p
description: "Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors."
field: w_z_gps_p
min: 0
max: 10
default_value: 0.4
default_value: 0.2
- name: inav_w_z_gps_v
description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
field: w_z_gps_v
min: 0
max: 10
default_value: 0.8
default_value: 0.1
- name: inav_w_xy_gps_p
description: "Weight of GPS coordinates in estimated UAV position and speed."
default_value: 1.0
Expand Down
18 changes: 10 additions & 8 deletions src/main/navigation/navigation.c
Original file line number Diff line number Diff line change
Expand Up @@ -4398,11 +4398,12 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(bool launchBypass)
if (posControl.flags.forcedRTHActivated) {
return NAV_FSM_EVENT_SWITCH_TO_RTH;
}
// CR115

/* WP mission activation control:
* canActivateWaypoint & waypointWasActivated are used to prevent WP mission
* auto restarting after interruption by Manual or RTH modes.
* WP mode must be deselected before it can be reactivated again. */
* WP mode must be deselected before it can be reactivated again
* WP Mode also inhibited when Mission Planner is active */
static bool waypointWasActivated = false;
bool canActivateWaypoint = isWaypointMissionValid();
bool wpRthFallbackIsActive = false;
Expand All @@ -4412,16 +4413,17 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(bool launchBypass)
} else {
if (waypointWasActivated && !FLIGHT_MODE(NAV_WP_MODE)) {
canActivateWaypoint = false;

if (!IS_RC_MODE_ACTIVE(BOXNAVWP)) {
canActivateWaypoint = true;
waypointWasActivated = false;
}
}

wpRthFallbackIsActive = IS_RC_MODE_ACTIVE(BOXNAVWP) && !canActivateWaypoint;
}

/* Pilot-triggered RTH, also fall-back for WP if there is no mission loaded.
* WP prevented from falling back to RTH if WP mission planner is active.
/* Pilot-triggered RTH, also fall-back for WP if no mission is loaded.
* Check for isExecutingRTH to prevent switching our from RTH in case of a brief GPS loss
* Without this loss of any of the canActivateNavigation && canActivateAltHold
* will kick us out of RTH state machine via NAV_FSM_EVENT_SWITCH_TO_IDLE and will prevent any of the fall-back
Expand All @@ -4431,7 +4433,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(bool launchBypass)
return NAV_FSM_EVENT_SWITCH_TO_RTH;
}
}
// CR115

// MANUAL mode has priority over WP/PH/AH
if (IS_RC_MODE_ACTIVE(BOXMANUAL)) {
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
Expand All @@ -4440,11 +4442,11 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(bool launchBypass)
// Pilot-activated waypoint mission. Fall-back to RTH if no mission loaded.
// Also check multimission mission change status before activating WP mode.
#ifdef USE_MULTI_MISSION
if (updateWpMissionChange() && IS_RC_MODE_ACTIVE(BOXNAVWP)) { // CR115
if (updateWpMissionChange() && IS_RC_MODE_ACTIVE(BOXNAVWP)) {
#else
if (IS_RC_MODE_ACTIVE(BOXNAVWP)) { // CR115
if (IS_RC_MODE_ACTIVE(BOXNAVWP)) {
#endif
if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateWaypoint && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { // CR115
if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateWaypoint && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) {
waypointWasActivated = true;
return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT;
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/programming/logic_condition.c
Original file line number Diff line number Diff line change
Expand Up @@ -483,8 +483,9 @@ static int logicConditionCompute(
}
break;

#ifdef LED_PIN
#ifdef USE_LED_STRIP
case LOGIC_CONDITION_LED_PIN_PWM:

if (operandA >=0 && operandA <= 100) {
ledPinStartPWM((uint8_t)operandA);
} else {
Expand Down
11 changes: 7 additions & 4 deletions src/main/target/FURYF4OSD/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,12 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1

// ICM42605/ICM42688P
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW180_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PA4

#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
Expand Down Expand Up @@ -112,10 +118,7 @@

#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_DPS310
#define USE_BARO_ALL

#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
Expand Down
1 change: 1 addition & 0 deletions src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO)
32 changes: 32 additions & 0 deletions src/main/target/IFLIGHT_BLITZ_H7_PRO/config.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/

#include <stdint.h>

#include "platform.h"

#include "fc/fc_msp_box.h"
#include "fc/config.h"

#include "io/piniobox.h"

void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
beeperConfigMutable()->pwmMode = true;
}
49 changes: 49 additions & 0 deletions src/main/target/IFLIGHT_BLITZ_H7_PRO/target.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/

#include <stdint.h>

#include "platform.h"

#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"

timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2

DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6

DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7
DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8
DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE

DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DMA_NONE

DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
Loading

0 comments on commit d7bb6e1

Please sign in to comment.