1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-19 14:25:16 +03:00
This commit is contained in:
breadoven 2022-09-27 13:36:05 +01:00
parent 1ed8d9481f
commit 16be85975a
7 changed files with 32 additions and 9 deletions

View file

@ -3342,6 +3342,16 @@ Deadband for heading trajectory PID controller. When heading error is below the
--- ---
### nav_land_detect_sensitivity
Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases.
| Default | Min | Max |
| --- | --- | --- |
| 5 | 1 | 15 |
---
### nav_land_maxalt_vspd ### nav_land_maxalt_vspd
Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s] Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]

View file

@ -2392,6 +2392,12 @@ groups:
default_value: OFF default_value: OFF
field: general.flags.disarm_on_landing field: general.flags.disarm_on_landing
type: bool type: bool
- name: nav_land_detect_sensitivity
description: "Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases."
default_value: 5
field: general.land_detect_sensitivity
min: 1
max: 15
- name: nav_use_midthr_for_althold - name: nav_use_midthr_for_althold
description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude"
default_value: OFF default_value: OFF

View file

@ -152,6 +152,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.max_altitude = SETTING_NAV_MAX_ALTITUDE_DEFAULT, .max_altitude = SETTING_NAV_MAX_ALTITUDE_DEFAULT,
.rth_trackback_distance = SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT, // Max distance allowed for RTH trackback .rth_trackback_distance = SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT, // Max distance allowed for RTH trackback
.waypoint_enforce_altitude = SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT, // Forces set wp altitude to be achieved .waypoint_enforce_altitude = SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT, // Forces set wp altitude to be achieved
.land_detect_sensitivity = SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT, // Changes sensitivity of landing detection
}, },
// MC-specific // MC-specific

View file

@ -263,6 +263,7 @@ typedef struct navConfig_s {
uint16_t max_altitude; // Max altitude when in AltHold mode (not Surface Following) uint16_t max_altitude; // Max altitude when in AltHold mode (not Surface Following)
uint16_t rth_trackback_distance; // RTH trackback maximum distance [m] uint16_t rth_trackback_distance; // RTH trackback maximum distance [m]
uint16_t waypoint_enforce_altitude; // Forces waypoint altitude to be achieved uint16_t waypoint_enforce_altitude; // Forces waypoint altitude to be achieved
uint8_t land_detect_sensitivity; // Sensitivity of landing detector
} general; } general;
struct { struct {

View file

@ -695,13 +695,15 @@ bool isFixedWingLandingDetected(void)
static timeMs_t fwLandingTimerStartAt; static timeMs_t fwLandingTimerStartAt;
static int16_t fwLandSetRollDatum; static int16_t fwLandSetRollDatum;
static int16_t fwLandSetPitchDatum; static int16_t fwLandSetPitchDatum;
const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f;
timeMs_t currentTimeMs = millis(); timeMs_t currentTimeMs = millis();
// Check horizontal and vertical volocities are low (cm/s) // Check horizontal and vertical velocities are low (cm/s)
bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < 50.0f && posControl.actualState.velXY < 100.0f; bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (50.0f * sensitivity) &&
posControl.actualState.velXY < (100.0f * sensitivity);
// Check angular rates are low (degs/s) // Check angular rates are low (degs/s)
bool gyroCondition = averageAbsGyroRates() < 2.0f; bool gyroCondition = averageAbsGyroRates() < (2.0f * sensitivity);
DEBUG_SET(DEBUG_LANDING, 2, velCondition); DEBUG_SET(DEBUG_LANDING, 2, velCondition);
DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); DEBUG_SET(DEBUG_LANDING, 3, gyroCondition);
@ -714,8 +716,9 @@ bool isFixedWingLandingDetected(void)
fixAxisCheck = true; fixAxisCheck = true;
fwLandingTimerStartAt = currentTimeMs; fwLandingTimerStartAt = currentTimeMs;
} else { } else {
bool isRollAxisStatic = ABS(fwLandSetRollDatum - attitude.values.roll) < 5; const uint8_t angleLimit = 5 * sensitivity;
bool isPitchAxisStatic = ABS(fwLandSetPitchDatum - attitude.values.pitch) < 5; bool isRollAxisStatic = ABS(fwLandSetRollDatum - attitude.values.roll) < angleLimit;
bool isPitchAxisStatic = ABS(fwLandSetPitchDatum - attitude.values.pitch) < angleLimit;
DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic); DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic);
DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic); DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic);
if (isRollAxisStatic && isPitchAxisStatic) { if (isRollAxisStatic && isPitchAxisStatic) {

View file

@ -737,11 +737,13 @@ bool isMulticopterLandingDetected(void)
return posControl.flags.resetLandingDetector = false; return posControl.flags.resetLandingDetector = false;
} }
const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f;
// check vertical and horizontal velocities are low (cm/s) // check vertical and horizontal velocities are low (cm/s)
bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < MC_LAND_CHECK_VEL_Z_MOVING && bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (MC_LAND_CHECK_VEL_Z_MOVING * sensitivity) &&
posControl.actualState.velXY < MC_LAND_CHECK_VEL_XY_MOVING; posControl.actualState.velXY < (MC_LAND_CHECK_VEL_XY_MOVING * sensitivity);
// check gyro rates are low (degs/s) // check gyro rates are low (degs/s)
bool gyroCondition = averageAbsGyroRates() < 2.0f; bool gyroCondition = averageAbsGyroRates() < (4.0f * sensitivity);
DEBUG_SET(DEBUG_LANDING, 2, velCondition); DEBUG_SET(DEBUG_LANDING, 2, velCondition);
DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); DEBUG_SET(DEBUG_LANDING, 3, gyroCondition);

View file

@ -40,7 +40,7 @@
#define MC_POS_CONTROL_JERK_LIMIT_CMSSS 1700.0f // jerk limit on horizontal acceleration (cm/s^3) #define MC_POS_CONTROL_JERK_LIMIT_CMSSS 1700.0f // jerk limit on horizontal acceleration (cm/s^3)
#define MC_LAND_CHECK_VEL_XY_MOVING 100.0f // cm/s #define MC_LAND_CHECK_VEL_XY_MOVING 100.0f // cm/s
#define MC_LAND_CHECK_VEL_Z_MOVING 25.0f // cm/s #define MC_LAND_CHECK_VEL_Z_MOVING 100.0f // cm/s
#define MC_LAND_THR_STABILISE_DELAY 1 // seconds #define MC_LAND_THR_STABILISE_DELAY 1 // seconds
#define MC_LAND_DESCEND_THROTTLE 40 // uS #define MC_LAND_DESCEND_THROTTLE 40 // uS
#define MC_LAND_SAFE_SURFACE 5.0f // cm #define MC_LAND_SAFE_SURFACE 5.0f // cm