AP_Motors: Heli: remove `output_armed_zero_throttle` and use identical `output_armed_stabilizing`

This commit is contained in:
Iampete1 2024-02-28 03:16:52 +00:00 committed by Randy Mackay
parent 4a310fb207
commit 1bf7792fe5
2 changed files with 1 additions and 17 deletions

View File

@ -211,11 +211,7 @@ void AP_MotorsHeli::output()
// block servo_test from happening at disarm // block servo_test from happening at disarm
_servo_test_cycle_counter = 0; _servo_test_cycle_counter = 0;
calculate_armed_scalars(); calculate_armed_scalars();
if (!get_interlock()) { output_armed_stabilizing();
output_armed_zero_throttle();
} else {
output_armed_stabilizing();
}
} else { } else {
output_disarmed(); output_disarmed();
} }
@ -237,17 +233,6 @@ void AP_MotorsHeli::output_armed_stabilizing()
move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in); move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in);
} }
// output_armed_zero_throttle - sends commands to the motors
void AP_MotorsHeli::output_armed_zero_throttle()
{
// if manual override active after arming, deactivate it and reinitialize servos
if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
reset_flight_controls();
}
move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in);
}
// output_disarmed - sends commands to the motors // output_disarmed - sends commands to the motors
void AP_MotorsHeli::output_disarmed() void AP_MotorsHeli::output_disarmed()
{ {

View File

@ -182,7 +182,6 @@ protected:
// output - sends commands to the motors // output - sends commands to the motors
void output_armed_stabilizing() override; void output_armed_stabilizing() override;
void output_armed_zero_throttle();
void output_disarmed(); void output_disarmed();
// external objects we depend upon // external objects we depend upon