mirror of https://github.com/ArduPilot/ardupilot
Copter: remove THR_MID
This commit is contained in:
parent
e9d8a28ec0
commit
48eb4cf674
|
@ -143,8 +143,8 @@ float Copter::get_pilot_desired_throttle(int16_t throttle_control)
|
||||||
|
|
||||||
// ensure reasonable throttle values
|
// ensure reasonable throttle values
|
||||||
throttle_control = constrain_int16(throttle_control,0,1000);
|
throttle_control = constrain_int16(throttle_control,0,1000);
|
||||||
|
|
||||||
// ensure mid throttle is set within a reasonable range
|
// ensure mid throttle is set within a reasonable range
|
||||||
g.throttle_mid = constrain_int16(g.throttle_mid,g.throttle_min+50,700);
|
|
||||||
float thr_mid = constrain_float(motors.get_throttle_hover(), 0.1f, 0.9f);
|
float thr_mid = constrain_float(motors.get_throttle_hover(), 0.1f, 0.9f);
|
||||||
|
|
||||||
// check throttle is above, below or in the deadband
|
// check throttle is above, below or in the deadband
|
||||||
|
@ -203,8 +203,6 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
|
||||||
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
|
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
|
||||||
float Copter::get_non_takeoff_throttle()
|
float Copter::get_non_takeoff_throttle()
|
||||||
{
|
{
|
||||||
// ensure mid throttle is set within a reasonable range
|
|
||||||
g.throttle_mid = constrain_int16(g.throttle_mid,g.throttle_min+50,700);
|
|
||||||
return MAX(0,motors.get_throttle_hover()/2.0f);
|
return MAX(0,motors.get_throttle_hover()/2.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -294,15 +294,6 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
||||||
|
|
||||||
// @Param: THR_MID
|
|
||||||
// @DisplayName: Throttle Mid Position
|
|
||||||
// @Description: The throttle output (0 ~ 1000) when throttle stick is in mid position. Used to scale the manual throttle so that the mid throttle stick position is close to the throttle required to hover
|
|
||||||
// @User: Standard
|
|
||||||
// @Range: 300 700
|
|
||||||
// @Units: Percent*10
|
|
||||||
// @Increment: 10
|
|
||||||
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
|
|
||||||
|
|
||||||
// @Param: THR_DZ
|
// @Param: THR_DZ
|
||||||
// @DisplayName: Throttle deadzone
|
// @DisplayName: Throttle deadzone
|
||||||
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
|
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
|
||||||
|
|
|
@ -292,7 +292,7 @@ public:
|
||||||
k_param_radio_tuning_low,
|
k_param_radio_tuning_low,
|
||||||
k_param_rc_speed = 192,
|
k_param_rc_speed = 192,
|
||||||
k_param_failsafe_battery_enabled,
|
k_param_failsafe_battery_enabled,
|
||||||
k_param_throttle_mid,
|
k_param_throttle_mid, // remove
|
||||||
k_param_failsafe_gps_enabled, // remove
|
k_param_failsafe_gps_enabled, // remove
|
||||||
k_param_rc_9,
|
k_param_rc_9,
|
||||||
k_param_rc_12,
|
k_param_rc_12,
|
||||||
|
@ -416,7 +416,6 @@ public:
|
||||||
//
|
//
|
||||||
AP_Int8 failsafe_throttle;
|
AP_Int8 failsafe_throttle;
|
||||||
AP_Int16 failsafe_throttle_value;
|
AP_Int16 failsafe_throttle_value;
|
||||||
AP_Int16 throttle_mid;
|
|
||||||
AP_Int16 throttle_deadzone;
|
AP_Int16 throttle_deadzone;
|
||||||
|
|
||||||
// Flight modes
|
// Flight modes
|
||||||
|
|
|
@ -547,9 +547,6 @@
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Throttle control gains
|
// Throttle control gains
|
||||||
//
|
//
|
||||||
#ifndef THR_MID_DEFAULT
|
|
||||||
# define THR_MID_DEFAULT 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef THR_DZ_DEFAULT
|
#ifndef THR_DZ_DEFAULT
|
||||||
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
|
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
|
||||||
|
|
Loading…
Reference in New Issue