Browse Source

Copter: remove THR_MIN

Equivalent is AP_Motors SPIN_MIN
master
Leonard Hall 9 years ago committed by Randy Mackay
parent
commit
dec9323127
  1. 2
      ArduCopter/ArduCopter.cpp
  2. 9
      ArduCopter/Parameters.cpp
  3. 3
      ArduCopter/Parameters.h
  4. 4
      ArduCopter/config.h
  5. 2
      ArduCopter/radio.cpp

2
ArduCopter/ArduCopter.cpp

@ -476,9 +476,9 @@ void Copter::one_hz_loop() @@ -476,9 +476,9 @@ void Copter::one_hz_loop()
motors.set_frame_orientation(g.frame_orientation);
// set all throttle channel settings
motors.set_throttle_range(g.throttle_min, channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
// set hover throttle
motors.set_hover_throttle(g.throttle_mid);
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
#endif
}

9
ArduCopter/Parameters.cpp

@ -278,15 +278,6 @@ const AP_Param::Info Copter::var_info[] = { @@ -278,15 +278,6 @@ const AP_Param::Info Copter::var_info[] = {
// @User: Standard
GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
// @Param: THR_MIN
// @DisplayName: Throttle Minimum
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
// @Units: Percent*10
// @Range: 0 300
// @Increment: 1
// @User: Standard
GSCALAR(throttle_min, "THR_MIN", THR_MIN_DEFAULT),
// @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel

3
ArduCopter/Parameters.h

@ -280,7 +280,7 @@ public: @@ -280,7 +280,7 @@ public:
k_param_rc_8,
k_param_rc_10,
k_param_rc_11,
k_param_throttle_min,
k_param_throttle_min, // remove
k_param_throttle_max, // remove
k_param_failsafe_throttle,
k_param_throttle_fs_action, // remove
@ -414,7 +414,6 @@ public: @@ -414,7 +414,6 @@ public:
// Throttle
//
AP_Int16 throttle_min;
AP_Int8 failsafe_throttle;
AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_mid;

4
ArduCopter/config.h

@ -551,10 +551,6 @@ @@ -551,10 +551,6 @@
# define THR_MID_DEFAULT 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
#endif
#ifndef THR_MIN_DEFAULT
# define THR_MIN_DEFAULT 130 // minimum throttle sent to the motors when armed and pilot throttle above zero
#endif
#ifndef THR_DZ_DEFAULT
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
#endif

2
ArduCopter/radio.cpp

@ -59,8 +59,8 @@ void Copter::init_rc_out() @@ -59,8 +59,8 @@ void Copter::init_rc_out()
motors.set_loop_rate(scheduler.get_loop_rate_hz());
motors.Init(); // motor initialisation
#if FRAME_CONFIG != HELI_FRAME
motors.set_throttle_range(g.throttle_min, channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
motors.set_hover_throttle(g.throttle_mid);
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
#endif
for(uint8_t i = 0; i < 5; i++) {

Loading…
Cancel
Save