Copter: disable aux channel ch7 for Tri

This commit is contained in:
Randy Mackay 2014-02-07 22:02:31 +09:00
parent 1426078cdb
commit 9b594dc5e1
1 changed files with 3 additions and 0 deletions

View File

@ -38,6 +38,9 @@ void AP_MotorsTri::Init()
motor_enabled[AP_MOTORS_MOT_1] = true;
motor_enabled[AP_MOTORS_MOT_2] = true;
motor_enabled[AP_MOTORS_MOT_4] = true;
// disable CH7 from being used as an aux output (i.e. for camera gimbal, etc)
RC_Channel_aux::disable_aux_channel(AP_MOTORS_CH_TRI_YAW);
}
// set update rate to motors - a value in hertz