mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-22 07:45:24 +03:00
first build
This commit is contained in:
parent
0d8e7889ca
commit
1c76c0b3d0
10 changed files with 49 additions and 63 deletions
|
@ -646,7 +646,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
|
|||
isAutoThrottleManuallyIncreased = false;
|
||||
}
|
||||
|
||||
rcCommand[THROTTLE] = constrain(correctedThrottleValue, getThrottleIdleValue(), motorConfig()->maxthrottle);
|
||||
rcCommand[THROTTLE] = setDesiredThrottle(correctedThrottleValue, false);
|
||||
}
|
||||
|
||||
#ifdef NAV_FIXED_WING_LANDING
|
||||
|
@ -661,7 +661,6 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
|
|||
(posControl.flags.estAglStatus == EST_TRUSTED && posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) {
|
||||
|
||||
// Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
|
||||
rcCommand[THROTTLE] = getThrottleIdleValue();
|
||||
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
|
||||
|
||||
// Stabilize ROLL axis on 0 degrees banking regardless of loiter radius and position
|
||||
|
@ -761,7 +760,7 @@ bool isFixedWingLandingDetected(void)
|
|||
*-----------------------------------------------------------*/
|
||||
void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs)
|
||||
{
|
||||
rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
|
||||
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->failsafe_throttle, true);
|
||||
|
||||
if (posControl.flags.estAltStatus >= EST_USABLE) {
|
||||
// target min descent rate 10m above takeoff altitude
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue