AP_MotorsCoax: remove disabling of output ch7
This commit is contained in:
parent
63fefae7cf
commit
20565580ed
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user