From 05246bf3b4086fd9c9519ace1c5a3c1ebe5a4add Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Thu, 19 Jan 2012 20:20:30 -0800 Subject: [PATCH] ArduCopter: Call APM_RC.enable_out for camera channels in init_camera() --- ArduCopter/Camera.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/Camera.pde b/ArduCopter/Camera.pde index 0937053f9b..047a7061ba 100644 --- a/ArduCopter/Camera.pde +++ b/ArduCopter/Camera.pde @@ -4,6 +4,8 @@ static void init_camera() { + APM_RC.enable_out(CH_CAM_PITCH); + APM_RC.enable_out(CH_CAM_ROLL); // ch 6 high(right) is down. g.rc_camera_pitch.set_angle(4500); g.rc_camera_roll.set_angle(4500);