From 793fb7f059b6d9a235f882bb45726328053f6115 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 15 Jul 2012 16:31:23 +0900 Subject: [PATCH] ArduCopter: added definition for yaw channels. APM1 uses channel 11 for camera's yaw servo, APM2 uses channel 8. This should allow all frame types except octacopters to potentially use a 3 axis camera mount. --- ArduCopter/config_channels.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/config_channels.h b/ArduCopter/config_channels.h index 40fa0eb833..b774ab19bb 100644 --- a/ArduCopter/config_channels.h +++ b/ArduCopter/config_channels.h @@ -25,13 +25,13 @@ // // #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 -/* Camera Pitch and Camera Roll: Not yet defined for APM2 - * They will likely be dependent on the frame config */ # define CH_CAM_PITCH CH_11 # define CH_CAM_ROLL CH_10 +# define CH_CAM_YAW CH_8 #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 # define CH_CAM_PITCH CH_5 # define CH_CAM_ROLL CH_6 +# define CH_CAM_YAW CH_11 #endif #endif // __ARDUCOPTER_CONFIG_MOTORS_H__