Browse Source

Copter: remove unused takeoff_trigger_dz parameter

mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
e5b25824eb
  1. 8
      ArduCopter/Parameters.cpp
  2. 3
      ArduCopter/Parameters.h
  3. 1
      ArduCopter/mode.cpp

8
ArduCopter/Parameters.cpp

@ -68,14 +68,6 @@ const AP_Param::Info Copter::var_info[] = { @@ -68,14 +68,6 @@ const AP_Param::Info Copter::var_info[] = {
// @Increment: 10
GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),
// @Param: PILOT_TKOFF_DZ
// @DisplayName: Takeoff trigger deadzone
// @Description: Offset from mid stick at which takeoff is triggered
// @User: Standard
// @Range: 0 500
// @Increment: 10
GSCALAR(takeoff_trigger_dz, "PILOT_TKOFF_DZ", THR_DZ_DEFAULT),
// @Param: PILOT_THR_BHV
// @DisplayName: Throttle stick behavior
// @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.

3
ArduCopter/Parameters.h

@ -207,7 +207,7 @@ public: @@ -207,7 +207,7 @@ public:
k_param_ch10_option_old,
k_param_ch11_option_old,
k_param_ch12_option_old,
k_param_takeoff_trigger_dz,
k_param_takeoff_trigger_dz_old,
k_param_gcs3,
k_param_gcs_pid_mask, // 126
@ -376,7 +376,6 @@ public: @@ -376,7 +376,6 @@ public:
AP_Float throttle_filt;
AP_Int16 throttle_behavior;
AP_Int16 takeoff_trigger_dz;
AP_Float pilot_takeoff_alt;
AP_Int16 rtl_altitude;

1
ArduCopter/mode.cpp

@ -381,6 +381,7 @@ bool Copter::Mode::_TakeOff::triggered(const float target_climb_rate) const @@ -381,6 +381,7 @@ bool Copter::Mode::_TakeOff::triggered(const float target_climb_rate) const
// can't takeoff unless we want to go up...
return false;
}
if (copter.motors->get_spool_mode() != AP_Motors::THROTTLE_UNLIMITED) {
// hold aircraft on the ground until rotor speed runup has finished
return false;

Loading…
Cancel
Save