Sub: Shift forward/lateral input channels up one to remove old ch5 gap

This commit is contained in:
Jacob Walser 2017-04-05 12:01:09 -04:00
parent d629d4ba9e
commit f2d9f1585e
2 changed files with 7 additions and 7 deletions

View File

@ -95,18 +95,18 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
channels[2] = constrain_int16((z+zTrim)*throttleScale+throttleBase,1100,1900); // throttle channels[2] = constrain_int16((z+zTrim)*throttleScale+throttleBase,1100,1900); // throttle
channels[3] = constrain_int16(r*rpyScale+rpyCenter,1100,1900); // yaw channels[3] = constrain_int16(r*rpyScale+rpyCenter,1100,1900); // yaw
//channels[4] = mode_switch_pwm; // for testing only
if (!roll_pitch_flag) { if (!roll_pitch_flag) {
// adjust forward and lateral with joystick input instead of roll and pitch // adjust forward and lateral with joystick input instead of roll and pitch
channels[5] = constrain_int16((x+xTrim)*rpyScale+rpyCenter,1100,1900); // forward for ROV channels[4] = constrain_int16((x+xTrim)*rpyScale+rpyCenter,1100,1900); // forward for ROV
channels[6] = constrain_int16((y+yTrim)*rpyScale+rpyCenter,1100,1900); // lateral for ROV channels[5] = constrain_int16((y+yTrim)*rpyScale+rpyCenter,1100,1900); // lateral for ROV
} else { } else {
// neutralize forward and lateral input while we are adjusting roll and pitch // neutralize forward and lateral input while we are adjusting roll and pitch
channels[5] = constrain_int16(xTrim*rpyScale+rpyCenter,1100,1900); // forward for ROV channels[4] = constrain_int16(xTrim*rpyScale+rpyCenter,1100,1900); // forward for ROV
channels[6] = constrain_int16(yTrim*rpyScale+rpyCenter,1100,1900); // lateral for ROV channels[5] = constrain_int16(yTrim*rpyScale+rpyCenter,1100,1900); // lateral for ROV
} }
channels[6] = 0; // Unused
channels[7] = cam_tilt; // camera tilt channels[7] = cam_tilt; // camera tilt
channels[8] = lights1; // lights 1 channels[8] = lights1; // lights 1
channels[9] = lights2; // lights 2 channels[9] = lights2; // lights 2

View File

@ -20,8 +20,8 @@ void Sub::init_rc_in()
channel_roll = RC_Channels::rc_channel(1); channel_roll = RC_Channels::rc_channel(1);
channel_throttle = RC_Channels::rc_channel(2); channel_throttle = RC_Channels::rc_channel(2);
channel_yaw = RC_Channels::rc_channel(3); channel_yaw = RC_Channels::rc_channel(3);
channel_forward = RC_Channels::rc_channel(5); channel_forward = RC_Channels::rc_channel(4);
channel_lateral = RC_Channels::rc_channel(6); channel_lateral = RC_Channels::rc_channel(5);
// set rc channel ranges // set rc channel ranges
channel_roll->set_angle(ROLL_PITCH_INPUT_MAX); channel_roll->set_angle(ROLL_PITCH_INPUT_MAX);