mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Rework prev commit a bit cleaner as suggested by Janne Mäntyharju
This commit is contained in:
parent
3fff788f95
commit
adbe965f35
@ -302,15 +302,25 @@ static void set_servos(void)
|
|||||||
#else
|
#else
|
||||||
// convert 0 to 100% into PWM
|
// convert 0 to 100% into PWM
|
||||||
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
|
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
|
||||||
if (g.airspeed_enabled == true) {
|
|
||||||
// We want to supress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
// We want to supress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
||||||
if((control_mode==Circle || control_mode>=FBW_B) && current_loc.alt-home.alt < 500 && airspeed< 500) {
|
/* Disable throttle if following conditions are met:
|
||||||
if(!(control_mode==Auto && takeoff_complete == false) g.channel_throttle.servo_out = 0;
|
1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
|
||||||
}
|
AND
|
||||||
} else {
|
2 - Our reported altitude is within 10 meters of the home altitude.
|
||||||
if((control_mode==Circle || control_mode>=FBW_B) && current_loc.alt-home.alt < 500 && g_gps->ground_speed < 500) {
|
3 - Our reported speed is under 5 meters per second.
|
||||||
if(!(control_mode==Auto && takeoff_complete == false) g.channel_throttle.servo_out = 0;
|
4 - We are not performing a takeoff in Auto mode
|
||||||
}
|
OR
|
||||||
|
5 - Home location is not set
|
||||||
|
*/
|
||||||
|
if (
|
||||||
|
(control_mode == CIRCLE || control_mode >= FLY_BY_WIRE_B) &&
|
||||||
|
(abs(home.alt - current_loc.alt) < 1000) &&
|
||||||
|
((g.airspeed_enabled ? airspeed : g_gps->ground_speed) < 500 ) &&
|
||||||
|
!(control_mode==Auto && takeoff_complete == false)
|
||||||
|
) {
|
||||||
|
g.channel_throttle.servo_out = 0;
|
||||||
|
g.channel_throttle.calc_pwm();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user