diff --git a/ArduCopter/Camera.pde b/ArduCopter/Camera.pde index 3a359d617b..e1d079f08e 100644 --- a/ArduCopter/Camera.pde +++ b/ArduCopter/Camera.pde @@ -41,7 +41,7 @@ camera_stabilization() */ // dont allow control mixing - g.rc_camera_roll.servo_out = (float)g.rc_camera_roll.servo_out * g.camera_roll_gain; + g.rc_camera_roll.servo_out = (float)-dcm.roll_sensor * g.camera_roll_gain; // limit //g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);