From 1dcd50e3be4c01dc5e36b6a2771e27ff904fc36f Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Fri, 27 Jan 2012 07:39:01 -0800 Subject: [PATCH] ArduCopter Tri: fix for enable_out of yaw servo, defined yaw servo for APM2 --- ArduCopter/config_channels.h | 3 +-- ArduCopter/motors_tri.pde | 1 + 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/config_channels.h b/ArduCopter/config_channels.h index fe6677e42a..b3a1e7263d 100644 --- a/ArduCopter/config_channels.h +++ b/ArduCopter/config_channels.h @@ -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 diff --git a/ArduCopter/motors_tri.pde b/ArduCopter/motors_tri.pde index dda4ba7638..3fbdb49e8f 100644 --- a/ArduCopter/motors_tri.pde +++ b/ArduCopter/motors_tri.pde @@ -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); }