From 4704faf60d79d853652b4b2a92847c7671043e37 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Thu, 17 Nov 2016 15:00:47 -0500 Subject: [PATCH] Sub: Revert to 29f8ce95, prior to deadzone PR --- ArduSub/Attitude.cpp | 5 ----- ArduSub/Sub.h | 1 - ArduSub/control_manual.cpp | 12 ++++++------ ArduSub/control_surface.cpp | 4 ++-- ArduSub/defines.h | 2 -- ArduSub/joystick.cpp | 5 +---- 6 files changed, 9 insertions(+), 20 deletions(-) diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index aaa1fee40d..7c49b35a60 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -128,11 +128,6 @@ void Sub::set_throttle_takeoff() pos_control.init_takeoff(); } -int16_t Sub::get_throttle_control_dz() -{ - return (channel_throttle->pwm_to_angle() + 1000)/2; -} - // get_pilot_desired_throttle - transform pilot's throttle input to make cruise throttle mid stick // used only for manual throttle modes // returns throttle output 0 to 1000 diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 36520febd9..ec4e090b90 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -1056,7 +1056,6 @@ private: void auto_terrain_recover_run(void); void translate_wpnav_rp(float &lateral_out, float &forward_out); - int16_t get_throttle_control_dz(); bool surface_init(bool ignore_flags); void surface_run(); diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index e1f2e0c573..afb3791167 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -27,10 +27,10 @@ void Sub::manual_run() motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); - motors.set_roll(channel_roll->norm_input_dz()*0.67f); - motors.set_pitch(channel_pitch->norm_input_dz()*0.67f); - motors.set_yaw(channel_yaw->norm_input_dz()*0.67f); - motors.set_throttle(channel_throttle->norm_input_dz()); - motors.set_forward(channel_forward->norm_input_dz()*0.67f); - motors.set_lateral(channel_lateral->norm_input_dz()*0.67f); + motors.set_roll(channel_roll->norm_input()*0.67f); + motors.set_pitch(channel_pitch->norm_input()*0.67f); + motors.set_yaw(channel_yaw->norm_input()*0.67f); + motors.set_throttle(channel_throttle->norm_input()); + motors.set_forward(channel_forward->norm_input()*0.67f); + motors.set_lateral(channel_lateral->norm_input()*0.67f); } diff --git a/ArduSub/control_surface.cpp b/ArduSub/control_surface.cpp index 4b19718436..98a6a3d446 100644 --- a/ArduSub/control_surface.cpp +++ b/ArduSub/control_surface.cpp @@ -59,6 +59,6 @@ void Sub::surface_run() pos_control.update_z_controller(); // pilot has control for repositioning - motors.set_forward(channel_forward->norm_input_dz()); - motors.set_lateral(channel_lateral->norm_input_dz()); + motors.set_forward(channel_forward->norm_input()); + motors.set_lateral(channel_lateral->norm_input()); } diff --git a/ArduSub/defines.h b/ArduSub/defines.h index 293a961474..f8c371ba50 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -507,5 +507,3 @@ enum ThrowModeState { #define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0) #define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1) #define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2) - -#define JOYSTICK_INITIAL_GAIN 0.5 diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 2db69f6f52..f1f24be431 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -21,7 +21,7 @@ namespace { int16_t video_switch = 1100; int16_t x_last, y_last, z_last; uint16_t buttons_prev; - float gain = JOYSTICK_INITIAL_GAIN; + float gain = 0.5; float maxGain = 1.0; float minGain = 0.25; int8_t numGainSettings = 4; @@ -203,21 +203,18 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) { } else { gain = 1.0f; } - RC_Channel::scale_dead_zones(gain); gcs_send_text_fmt(MAV_SEVERITY_INFO,"#Gain: %2.0f%%",gain*100); } break; case JSButton::button_function_t::k_gain_inc: if ( !held ) { gain = constrain_float(gain + (maxGain-minGain)/(numGainSettings-1), minGain, maxGain); - RC_Channel::scale_dead_zones(gain); gcs_send_text_fmt(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",gain*100); } break; case JSButton::button_function_t::k_gain_dec: if ( !held ) { gain = constrain_float(gain - (maxGain-minGain)/(numGainSettings-1), minGain, maxGain); - RC_Channel::scale_dead_zones(gain); gcs_send_text_fmt(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",gain*100); } break;