mirror of https://github.com/ArduPilot/ardupilot
fix for Camera Roll
This commit is contained in:
parent
4ad9f2db7c
commit
97670246ff
|
@ -41,7 +41,7 @@ camera_stabilization()
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// dont allow control mixing
|
// 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
|
// limit
|
||||||
//g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);
|
//g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);
|
||||||
|
|
Loading…
Reference in New Issue