mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: don't spin motors in ALTHOLD with zero throttle
This commit is contained in:
parent
dbd6524f9f
commit
838fb3f4e2
@ -1891,14 +1891,20 @@ void update_throttle_mode(void)
|
||||
break;
|
||||
|
||||
case THROTTLE_HOLD:
|
||||
// alt hold plus pilot input of climb rate
|
||||
pilot_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
|
||||
if( sonar_alt_health >= SONAR_ALT_HEALTH_MAX ) {
|
||||
// if sonar is ok, use surface tracking
|
||||
get_throttle_surface_tracking(pilot_climb_rate); // this function calls set_target_alt_for_reporting for us
|
||||
if(ap.auto_armed) {
|
||||
// alt hold plus pilot input of climb rate
|
||||
pilot_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
|
||||
if( sonar_alt_health >= SONAR_ALT_HEALTH_MAX ) {
|
||||
// if sonar is ok, use surface tracking
|
||||
get_throttle_surface_tracking(pilot_climb_rate); // this function calls set_target_alt_for_reporting for us
|
||||
}else{
|
||||
// if no sonar fall back stabilize rate controller
|
||||
get_throttle_rate_stabilized(pilot_climb_rate); // this function calls set_target_alt_for_reporting for us
|
||||
}
|
||||
}else{
|
||||
// if no sonar fall back stabilize rate controller
|
||||
get_throttle_rate_stabilized(pilot_climb_rate); // this function calls set_target_alt_for_reporting for us
|
||||
// pilot's throttle must be at zero so keep motors off
|
||||
set_throttle_out(0, false);
|
||||
set_target_alt_for_reporting(0);
|
||||
}
|
||||
break;
|
||||
|
||||
@ -1907,8 +1913,11 @@ void update_throttle_mode(void)
|
||||
if(ap.auto_armed) {
|
||||
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
|
||||
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
|
||||
}else{
|
||||
// pilot's throttle must be at zero so keep motors off
|
||||
set_throttle_out(0, false);
|
||||
set_target_alt_for_reporting(0);
|
||||
}
|
||||
// To-Do: explicitly set what the throttle output should be (probably min throttle). Without setting it the throttle is simply left in it's last position although that is probably zero throttle anyway
|
||||
break;
|
||||
|
||||
case THROTTLE_LAND:
|
||||
|
Loading…
Reference in New Issue
Block a user