Skip to content

Commit

Permalink
Plane: set_servos_idle: output left and right throttles
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Oct 31, 2023
1 parent 8061b1b commit 5087a42
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -371,7 +371,14 @@ void Plane::set_servos_idle(void)
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value);
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value);
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value);

SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0);

SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle);
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft);
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight);

}

Expand Down

0 comments on commit 5087a42

Please sign in to comment.