mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: bug fix for heli_control_acro throttle
This commit is contained in:
parent
c73c9f03a5
commit
1648ecc6e5
@ -17,6 +17,7 @@ static bool heli_acro_init(bool ignore_checks)
|
||||
static void heli_acro_run()
|
||||
{
|
||||
int16_t target_roll, target_pitch, target_yaw;
|
||||
int16_t pilot_throttle_scaled;
|
||||
|
||||
// if not armed or main rotor not up to full speed clear stabilized rate errors
|
||||
// unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
||||
@ -29,7 +30,14 @@ static void heli_acro_run()
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw);
|
||||
|
||||
// get pilot's desired throttle
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
|
||||
|
||||
// run attitude controller
|
||||
attitude_control.ratebf_rpy(target_roll, target_pitch, target_yaw);
|
||||
|
||||
// output pilot's throttle without angle boost
|
||||
attitude_control.set_throttle_out(pilot_throttle_scaled, false);
|
||||
}
|
||||
|
||||
#endif //HELI_FRAME
|
||||
|
Loading…
Reference in New Issue
Block a user