From 3517964e14f660aa7c3f4d0d9958dc9a7b22c31d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Feb 2012 23:51:53 +0900 Subject: [PATCH] ArduCopter - Camera.pde - turn off camera pitch control (which uses channel 6) when channel 6 is being used for tuning. --- ArduCopter/Camera.pde | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/ArduCopter/Camera.pde b/ArduCopter/Camera.pde index f0f3df9f48..8341f2b40b 100644 --- a/ArduCopter/Camera.pde +++ b/ArduCopter/Camera.pde @@ -20,20 +20,19 @@ camera_stabilization() { // PITCH // ----- - // allow control mixing - g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here. - g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor); - + // Allow user to control camera pitch with channel 6 (mixed with pitch DCM) + if(g.radio_tuning == 0) { + g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); + g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor); + }else{ + // unless channel 6 is already being used for tuning + g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1; + } g.rc_camera_pitch.servo_out = (float)g.rc_camera_pitch.servo_out * g.camera_pitch_gain; // limit //g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500); - // dont allow control mixing - /* - g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1; - */ - // ROLL // -----