mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 14:25:16 +03:00
first build
This commit is contained in:
parent
bef8acca51
commit
26deae54bb
5 changed files with 32 additions and 12 deletions
|
@ -118,6 +118,7 @@ uint8_t motorControlEnable = false;
|
||||||
static bool isRXDataNew;
|
static bool isRXDataNew;
|
||||||
static disarmReason_t lastDisarmReason = DISARM_NONE;
|
static disarmReason_t lastDisarmReason = DISARM_NONE;
|
||||||
timeUs_t lastDisarmTimeUs = 0;
|
timeUs_t lastDisarmTimeUs = 0;
|
||||||
|
timeMs_t emergInflightRearmTimeout = 0;
|
||||||
|
|
||||||
static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible
|
static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible
|
||||||
static timeMs_t prearmActivationTime = 0;
|
static timeMs_t prearmActivationTime = 0;
|
||||||
|
@ -176,7 +177,7 @@ int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband)
|
||||||
{
|
{
|
||||||
int16_t stickDeflection = 0;
|
int16_t stickDeflection = 0;
|
||||||
|
|
||||||
#if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914
|
#if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914
|
||||||
const int16_t value = rawData - PWM_RANGE_MIDDLE;
|
const int16_t value = rawData - PWM_RANGE_MIDDLE;
|
||||||
if (value < -500) {
|
if (value < -500) {
|
||||||
stickDeflection = -500;
|
stickDeflection = -500;
|
||||||
|
@ -186,9 +187,9 @@ int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband)
|
||||||
stickDeflection = value;
|
stickDeflection = value;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500);
|
stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
stickDeflection = applyDeadbandRescaled(stickDeflection, deadband, -500, 500);
|
stickDeflection = applyDeadbandRescaled(stickDeflection, deadband, -500, 500);
|
||||||
return rcLookup(stickDeflection, rate);
|
return rcLookup(stickDeflection, rate);
|
||||||
}
|
}
|
||||||
|
@ -432,6 +433,7 @@ void disarm(disarmReason_t disarmReason)
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
lastDisarmReason = disarmReason;
|
lastDisarmReason = disarmReason;
|
||||||
lastDisarmTimeUs = micros();
|
lastDisarmTimeUs = micros();
|
||||||
|
emergInflightRearmTimeout = US2MS(lastDisarmTimeUs) + (isProbablyStillFlying() ? 5000 : 0);
|
||||||
DISABLE_ARMING_FLAG(ARMED);
|
DISABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
#ifdef USE_BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
|
@ -509,6 +511,11 @@ void releaseSharedTelemetryPorts(void) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool emergInflightRearmEnabled(void)
|
||||||
|
{
|
||||||
|
return millis() < emergInflightRearmTimeout;
|
||||||
|
}
|
||||||
|
|
||||||
void tryArm(void)
|
void tryArm(void)
|
||||||
{
|
{
|
||||||
updateArmingStatus();
|
updateArmingStatus();
|
||||||
|
@ -529,9 +536,10 @@ void tryArm(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||||
if (!isArmingDisabled() || emergencyArmingIsEnabled() || LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) {
|
if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled() ||
|
||||||
|
LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) {
|
||||||
#else
|
#else
|
||||||
if (!isArmingDisabled() || emergencyArmingIsEnabled()) {
|
if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled()) {
|
||||||
#endif
|
#endif
|
||||||
// If nav_extra_arming_safety was bypassed we always
|
// If nav_extra_arming_safety was bypassed we always
|
||||||
// allow bypassing it even without the sticks set
|
// allow bypassing it even without the sticks set
|
||||||
|
@ -837,7 +845,7 @@ static float calculateThrottleTiltCompensationFactor(uint8_t throttleTiltCompens
|
||||||
|
|
||||||
void taskMainPidLoop(timeUs_t currentTimeUs)
|
void taskMainPidLoop(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
|
|
||||||
cycleTime = getTaskDeltaTime(TASK_SELF);
|
cycleTime = getTaskDeltaTime(TASK_SELF);
|
||||||
dT = (float)cycleTime * 0.000001f;
|
dT = (float)cycleTime * 0.000001f;
|
||||||
|
|
||||||
|
|
|
@ -43,6 +43,7 @@ void tryArm(void);
|
||||||
disarmReason_t getDisarmReason(void);
|
disarmReason_t getDisarmReason(void);
|
||||||
|
|
||||||
bool emergencyArmingUpdate(bool armingSwitchIsOn);
|
bool emergencyArmingUpdate(bool armingSwitchIsOn);
|
||||||
|
bool emergInflightRearmEnabled(void);
|
||||||
|
|
||||||
bool areSensorsCalibrating(void);
|
bool areSensorsCalibrating(void);
|
||||||
float getFlightTime(void);
|
float getFlightTime(void);
|
||||||
|
|
|
@ -228,6 +228,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
||||||
static navWapointHeading_t wpHeadingControl;
|
static navWapointHeading_t wpHeadingControl;
|
||||||
navigationPosControl_t posControl;
|
navigationPosControl_t posControl;
|
||||||
navSystemStatus_t NAV_Status;
|
navSystemStatus_t NAV_Status;
|
||||||
|
static bool landingDetectorIsActive;
|
||||||
|
|
||||||
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
||||||
|
|
||||||
|
@ -2803,14 +2804,14 @@ void updateLandingStatus(timeMs_t currentTimeMs)
|
||||||
}
|
}
|
||||||
lastUpdateTimeMs = currentTimeMs;
|
lastUpdateTimeMs = currentTimeMs;
|
||||||
|
|
||||||
static bool landingDetectorIsActive;
|
|
||||||
|
|
||||||
DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive);
|
DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive);
|
||||||
DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED));
|
DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED));
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED)) {
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
resetLandingDetector();
|
if (!emergInflightRearmEnabled()) {
|
||||||
landingDetectorIsActive = false;
|
resetLandingDetector();
|
||||||
|
landingDetectorIsActive = false;
|
||||||
|
}
|
||||||
if (!IS_RC_MODE_ACTIVE(BOXARM)) {
|
if (!IS_RC_MODE_ACTIVE(BOXARM)) {
|
||||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED);
|
DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED);
|
||||||
}
|
}
|
||||||
|
@ -2852,6 +2853,15 @@ bool isFlightDetected(void)
|
||||||
return STATE(AIRPLANE) ? isFixedWingFlying() : isMulticopterFlying();
|
return STATE(AIRPLANE) ? isFixedWingFlying() : isMulticopterFlying();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isProbablyStillFlying(void)
|
||||||
|
{
|
||||||
|
bool inFlightSanityCheck = false;
|
||||||
|
if (STATE(AIRPLANE)) {
|
||||||
|
inFlightSanityCheck = isGPSHeadingValid();
|
||||||
|
}
|
||||||
|
return landingDetectorIsActive && !STATE(LANDING_DETECTED) && inFlightSanityCheck;
|
||||||
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
* Z-position controller
|
* Z-position controller
|
||||||
*-----------------------------------------------------------*/
|
*-----------------------------------------------------------*/
|
||||||
|
@ -3801,7 +3811,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
||||||
canActivateWaypoint = false;
|
canActivateWaypoint = false;
|
||||||
|
|
||||||
// Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight)
|
// Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight)
|
||||||
canActivateLaunchMode = isNavLaunchEnabled();
|
canActivateLaunchMode = isNavLaunchEnabled() && (!sensors(SENSOR_GPS) || (sensors(SENSOR_GPS) && !isGPSHeadingValid()));
|
||||||
}
|
}
|
||||||
|
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
|
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
|
||||||
|
|
|
@ -610,6 +610,7 @@ const char * fixedWingLaunchStateMessage(void);
|
||||||
float calculateAverageSpeed(void);
|
float calculateAverageSpeed(void);
|
||||||
|
|
||||||
void updateLandingStatus(timeMs_t currentTimeMs);
|
void updateLandingStatus(timeMs_t currentTimeMs);
|
||||||
|
bool isProbablyStillFlying(void);
|
||||||
|
|
||||||
const navigationPIDControllers_t* getNavigationPIDControllers(void);
|
const navigationPIDControllers_t* getNavigationPIDControllers(void);
|
||||||
|
|
||||||
|
|
|
@ -692,7 +692,7 @@ bool isFixedWingFlying(void)
|
||||||
bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f;
|
bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f;
|
||||||
bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING;
|
bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING;
|
||||||
|
|
||||||
return (isImuHeadingValid() && throttleCondition && velCondition) || launchCondition;
|
return (isGPSHeadingValid() && throttleCondition && velCondition) || launchCondition;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue