1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Removed mc_min_fly_throttle, added mc_auto_disarm_delay

This commit is contained in:
theArchLadder 2016-06-02 11:29:21 +02:00
parent 85760224c1
commit e01e951ab1
5 changed files with 4 additions and 8 deletions

View file

@ -246,7 +246,7 @@ void resetNavConfig(navConfig_t * navConfig)
// MC-specific // MC-specific
navConfig->mc_max_bank_angle = 30; // 30 deg navConfig->mc_max_bank_angle = 30; // 30 deg
navConfig->mc_hover_throttle = 1500; navConfig->mc_hover_throttle = 1500;
navConfig->mc_min_fly_throttle = 1200; navConfig->mc_auto_disarm_delay = 2000;
// Fixed wing // Fixed wing
navConfig->fw_max_bank_angle = 20; // 30 deg navConfig->fw_max_bank_angle = 20; // 30 deg

View file

@ -115,7 +115,7 @@ typedef struct navConfig_s {
uint8_t mc_max_bank_angle; // multicopter max banking angle (deg) uint8_t mc_max_bank_angle; // multicopter max banking angle (deg)
uint16_t mc_hover_throttle; // multicopter hover throttle uint16_t mc_hover_throttle; // multicopter hover throttle
uint16_t mc_min_fly_throttle; // multicopter minimum throttle to consider machine flying uint16_t mc_auto_disarm_delay; // multicopter safety delay for landing detector
uint16_t fw_cruise_throttle; // Cruise throttle uint16_t fw_cruise_throttle; // Cruise throttle
uint16_t fw_min_throttle; // Minimum allowed throttle in auto mode uint16_t fw_min_throttle; // Minimum allowed throttle in auto mode

View file

@ -520,9 +520,6 @@ bool isMulticopterLandingDetected(void)
isAtMinimalThrust = rcCommandAdjustedThrottle < (landingThrSum / landingThrSamples - 40); isAtMinimalThrust = rcCommandAdjustedThrottle < (landingThrSum / landingThrSamples - 40);
} }
// TODO: This setting is no longer needed, remove or reuse it for LAND_DETECTOR_TRIGGER_TIME_MS
//posControl.navConfig->mc_min_fly_throttle;
bool possibleLandingDetected = /*hasHadSomeVelocity &&*/ isAtMinimalThrust && !verticalMovement && !horizontalMovement; bool possibleLandingDetected = /*hasHadSomeVelocity &&*/ isAtMinimalThrust && !verticalMovement && !horizontalMovement;
navDebug[0] = /*hasHadSomeVelocity * 1000 +*/ isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1; navDebug[0] = /*hasHadSomeVelocity * 1000 +*/ isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1;
@ -542,7 +539,7 @@ bool isMulticopterLandingDetected(void)
return false; return false;
} }
else { else {
return ((currentTime - landingTimer) > (LAND_DETECTOR_TRIGGER_TIME_MS * 1000)) ? true : false; return ((currentTime - landingTimer) > (posControl.navConfig->mc_auto_disarm_delay * 1000)) ? true : false;
} }
} }

View file

@ -23,7 +23,6 @@
#include "config/runtime_config.h" #include "config/runtime_config.h"
#define LAND_DETECTOR_TRIGGER_TIME_MS 2000 // 2 seconds
#define MIN_POSITION_UPDATE_RATE_HZ 5 // Minimum position update rate at which XYZ controllers would be applied #define MIN_POSITION_UPDATE_RATE_HZ 5 // Minimum position update rate at which XYZ controllers would be applied
#define NAV_THROTTLE_CUTOFF_FREQENCY_HZ 4 // low-pass filter on throttle output #define NAV_THROTTLE_CUTOFF_FREQENCY_HZ 4 // low-pass filter on throttle output
#define NAV_ACCEL_CUTOFF_FREQUENCY_HZ 2 // low-pass filter on XY-acceleration target #define NAV_ACCEL_CUTOFF_FREQUENCY_HZ 2 // low-pass filter on XY-acceleration target

View file

@ -602,7 +602,7 @@ const clivalue_t valueTable[] = {
{ "nav_mc_bank_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.mc_max_bank_angle, .config.minmax = { 15, 45 }, 0 }, { "nav_mc_bank_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.mc_max_bank_angle, .config.minmax = { 15, 45 }, 0 },
{ "nav_mc_hover_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_hover_throttle, .config.minmax = { 1000, 2000 }, 0 }, { "nav_mc_hover_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_hover_throttle, .config.minmax = { 1000, 2000 }, 0 },
{ "nav_mc_min_fly_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_min_fly_throttle, .config.minmax = { 1000, 2000 }, 0 }, { "nav_mc_auto_disarm_delay", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_auto_disarm_delay, .config.minmax = { 100, 10000 }, 0 },
{ "nav_fw_cruise_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_cruise_throttle, .config.minmax = { 1000, 2000 }, 0 }, { "nav_fw_cruise_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_cruise_throttle, .config.minmax = { 1000, 2000 }, 0 },
{ "nav_fw_min_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_min_throttle, .config.minmax = { 1000, 2000 }, 0 }, { "nav_fw_min_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_min_throttle, .config.minmax = { 1000, 2000 }, 0 },