AP_MotorsCoax: remove disabling of output ch7

This commit is contained in:
Randy Mackay 2016-02-11 16:57:02 +09:00
parent 63fefae7cf
commit 20565580ed
1 changed files with 0 additions and 3 deletions

View File

@ -79,9 +79,6 @@ void AP_MotorsCoax::Init()
_servo2.set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
_servo3.set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
_servo4.set_angle(AP_MOTORS_COAX_SERVO_INPUT_RANGE);
// disable CH7 from being used as an aux output (i.e. for camera gimbal, etc)
RC_Channel_aux::disable_aux_channel(CH_7);
}
// set update rate to motors - a value in hertz