Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Motors: Heli: remove output_armed_zero_throttle and use identical output_armed_stabilizing #26343

Merged
merged 1 commit into from Mar 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
17 changes: 1 addition & 16 deletions libraries/AP_Motors/AP_MotorsHeli.cpp
Expand Up @@ -211,11 +211,7 @@ void AP_MotorsHeli::output()
// block servo_test from happening at disarm
_servo_test_cycle_counter = 0;
calculate_armed_scalars();
if (!get_interlock()) {
output_armed_zero_throttle();
} else {
output_armed_stabilizing();
}
output_armed_stabilizing();
} else {
output_disarmed();
}
Expand All @@ -237,17 +233,6 @@ void AP_MotorsHeli::output_armed_stabilizing()
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
void AP_MotorsHeli::output_disarmed()
{
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_Motors/AP_MotorsHeli.h
Expand Up @@ -182,7 +182,6 @@ class AP_MotorsHeli : public AP_Motors {

// output - sends commands to the motors
void output_armed_stabilizing() override;
void output_armed_zero_throttle();
void output_disarmed();

// external objects we depend upon
Expand Down