Sub: Remove unneeded camtilt input.

This commit is contained in:
Rustom Jehangir 2016-02-02 13:40:26 -08:00 committed by Andrew Tridgell
parent 02b8069270
commit c31ccd242f

View File

@ -185,7 +185,7 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
channels[5] = x*rpyScale+rpyCenter; // forward for ROV channels[5] = x*rpyScale+rpyCenter; // forward for ROV
channels[6] = y*rpyScale+rpyCenter; // strafe for ROV channels[6] = y*rpyScale+rpyCenter; // strafe for ROV
channels[7] = camTilt; // camera tilt channels[7] = camTilt; // camera tilt
channels[8] = camTilt; channels[8] = 0;
channels[9] = 0; channels[9] = 0;
// record that rc are overwritten so we can trigger a failsafe if we lose contact with groundstation // record that rc are overwritten so we can trigger a failsafe if we lose contact with groundstation