ArduCopter Tri: fix for enable_out of yaw servo, defined yaw servo for APM2

This commit is contained in:
Pat Hickey 2012-01-27 07:39:01 -08:00
parent 64f59e4dd5
commit 1dcd50e3be
2 changed files with 2 additions and 2 deletions

View File

@ -49,8 +49,7 @@
//
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
/* TODO find out correct channel for APM2 TRI_YAW */
# define CH_TRI_YAW (-1)
# define CH_TRI_YAW CH_7
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define CH_TRI_YAW CH_7
#endif

View File

@ -13,6 +13,7 @@ static void motors_output_enable()
APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_4);
APM_RC.enable_out(CH_TRI_YAW);
}