diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 3819a5e159..a1d36aae1d 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -21,10 +21,6 @@ namespace { int16_t video_switch = 1100; int16_t x_last, y_last, z_last; uint16_t buttons_prev; - float gain = 0.5; - float maxGain = 1.0; - float minGain = 0.25; - int8_t numGainSettings = 4; } void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) { @@ -32,8 +28,8 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t uint32_t tnow_ms = millis(); - float rpyScale = 0.4*gain; // Scale -1000-1000 to -400-400 with gain - float throttleScale = 0.8*gain; // Scale 0-1000 to 0-800 with gain + float rpyScale = 0.4; // Scale -1000-1000 to -400-400 + float throttleScale = 0.8; // Scale 0-1000 to 0-800 int16_t rpyCenter = 1500; int16_t throttleBase = 1500-500*throttleScale; @@ -188,20 +184,20 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift) { static bool lowGain = false; lowGain = !lowGain; if ( lowGain ) { - gain = 0.5f; + motors.set_gain(0.0f); } else { - gain = 1.0f; + motors.set_gain(1.0f); } - gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",gain*100); + gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",motors.get_gain()*100); } break; case JSButton::button_function_t::k_gain_inc: - gain = constrain_float(gain + (maxGain-minGain)/(numGainSettings-1), minGain, maxGain); - gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",gain*100); + motors.increase_gain(); + gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",motors.get_gain()*100); break; case JSButton::button_function_t::k_gain_dec: - gain = constrain_float(gain - (maxGain-minGain)/(numGainSettings-1), minGain, maxGain); - gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",gain*100); + motors.decrease_gain(); + gcs_send_text_fmt(MAV_SEVERITY_INFO,"Gain: %2.0f%%",motors.get_gain()*100); break; case JSButton::button_function_t::k_trim_roll_inc: rollTrim = constrain_float(rollTrim+10,-200,200);