mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
TradHeli: Modify Throttle_Auto to prevent helis from pushing hard downward while running up the motor. We will set the collective pitch to stab_col_min which should result in a mild downward pressure if the user has set their parameters correctly.
This commit is contained in:
parent
ffb605d06d
commit
f67d95ac75
@ -1995,8 +1995,13 @@ void update_throttle_mode(void)
|
|||||||
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
|
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
|
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
|
||||||
}else{
|
}else{
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
// collective pitch should not be full negative to avoid harshing the mechanics. Use Stab Coll Min.
|
||||||
|
set_throttle_out(motors.stab_col_min*10, false);
|
||||||
|
#else
|
||||||
// pilot's throttle must be at zero so keep motors off
|
// pilot's throttle must be at zero so keep motors off
|
||||||
set_throttle_out(0, false);
|
set_throttle_out(0, false);
|
||||||
|
#endif // HELI_FRAME
|
||||||
// deactivate accel based throttle controller
|
// deactivate accel based throttle controller
|
||||||
throttle_accel_deactivate();
|
throttle_accel_deactivate();
|
||||||
set_target_alt_for_reporting(0);
|
set_target_alt_for_reporting(0);
|
||||||
|
Loading…
Reference in New Issue
Block a user