mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_MotorsHeli: remove output_armed_not_stabilizing
This commit is contained in:
parent
5cd4b78918
commit
f02e8f8e01
@ -207,10 +207,8 @@ void AP_MotorsHeli::output()
|
||||
calculate_armed_scalars();
|
||||
if (!_flags.interlock) {
|
||||
output_armed_zero_throttle();
|
||||
} else if (_flags.stabilizing) {
|
||||
output_armed_stabilizing();
|
||||
} else {
|
||||
output_armed_not_stabilizing();
|
||||
output_armed_stabilizing();
|
||||
}
|
||||
} else {
|
||||
output_disarmed();
|
||||
@ -230,19 +228,6 @@ void AP_MotorsHeli::output_armed_stabilizing()
|
||||
update_motor_control(ROTOR_CONTROL_ACTIVE);
|
||||
}
|
||||
|
||||
void AP_MotorsHeli::output_armed_not_stabilizing()
|
||||
{
|
||||
// if manual override active after arming, deactivate it and reinitialize servos
|
||||
if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
|
||||
reset_flight_controls();
|
||||
}
|
||||
|
||||
// helicopters always run stabilizing flight controls
|
||||
move_actuators(_roll_control_input, _pitch_control_input, _throttle_control_input, _yaw_control_input);
|
||||
|
||||
update_motor_control(ROTOR_CONTROL_ACTIVE);
|
||||
}
|
||||
|
||||
// output_armed_zero_throttle - sends commands to the motors
|
||||
void AP_MotorsHeli::output_armed_zero_throttle()
|
||||
{
|
||||
|
@ -178,7 +178,6 @@ protected:
|
||||
|
||||
// output - sends commands to the motors
|
||||
void output_armed_stabilizing();
|
||||
void output_armed_not_stabilizing();
|
||||
void output_armed_zero_throttle();
|
||||
void output_disarmed();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user