mirror of https://github.com/ArduPilot/ardupilot
Sub: Revert to 29f8ce95
, prior to deadzone PR
This commit is contained in:
parent
e49f6fb8a6
commit
4704faf60d
|
@ -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
|
||||
|
|
|
@ -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();
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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());
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue