Browse Source

Copter: fixed aux servos in RC failsafe

we should always output to channels
master
Andrew Tridgell 8 years ago
parent
commit
2ba6e7af35
  1. 9
      ArduCopter/motors.cpp
  2. 3
      ArduCopter/radio.cpp

9
ArduCopter/motors.cpp

@ -292,6 +292,12 @@ void Copter::motors_output() @@ -292,6 +292,12 @@ void Copter::motors_output()
// output any servo channels
SRV_Channels::calc_pwm();
// cork now, so that all channel outputs happen at once
hal.rcout->cork();
// update output on any aux channels, for manual passthru
SRV_Channels::output_ch_all();
// check if we are performing the motor test
if (ap.motor_test) {
@ -309,6 +315,9 @@ void Copter::motors_output() @@ -309,6 +315,9 @@ void Copter::motors_output()
// send output signals to motors
motors->output();
}
// push all channels
hal.rcout->push();
}
// check for pilot stick input to trigger lost vehicle alarm

3
ArduCopter/radio.cpp

@ -99,9 +99,6 @@ void Copter::read_radio() @@ -99,9 +99,6 @@ void Copter::read_radio()
ap.rc_receiver_present = true;
}
// update output on any aux channels, for manual passthru
SRV_Channels::output_ch_all();
// pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters)
radio_passthrough_to_motors();

Loading…
Cancel
Save