Copter: remove THR_MIN
Equivalent is AP_Motors SPIN_MIN
This commit is contained in:
parent
6a1bdebf25
commit
dec9323127
@ -476,9 +476,9 @@ void Copter::one_hz_loop()
|
|||||||
motors.set_frame_orientation(g.frame_orientation);
|
motors.set_frame_orientation(g.frame_orientation);
|
||||||
|
|
||||||
// set all throttle channel settings
|
// 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
|
// set hover throttle
|
||||||
motors.set_hover_throttle(g.throttle_mid);
|
motors.set_hover_throttle(g.throttle_mid);
|
||||||
|
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -278,15 +278,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
|
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
|
// @Param: FS_THR_ENABLE
|
||||||
// @DisplayName: Throttle Failsafe 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
|
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||||
|
@ -280,7 +280,7 @@ public:
|
|||||||
k_param_rc_8,
|
k_param_rc_8,
|
||||||
k_param_rc_10,
|
k_param_rc_10,
|
||||||
k_param_rc_11,
|
k_param_rc_11,
|
||||||
k_param_throttle_min,
|
k_param_throttle_min, // remove
|
||||||
k_param_throttle_max, // remove
|
k_param_throttle_max, // remove
|
||||||
k_param_failsafe_throttle,
|
k_param_failsafe_throttle,
|
||||||
k_param_throttle_fs_action, // remove
|
k_param_throttle_fs_action, // remove
|
||||||
@ -414,7 +414,6 @@ public:
|
|||||||
|
|
||||||
// Throttle
|
// Throttle
|
||||||
//
|
//
|
||||||
AP_Int16 throttle_min;
|
|
||||||
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_mid;
|
||||||
|
@ -551,10 +551,6 @@
|
|||||||
# define THR_MID_DEFAULT 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
|
# define THR_MID_DEFAULT 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
|
||||||
#endif
|
#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
|
#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
|
||||||
#endif
|
#endif
|
||||||
|
@ -59,8 +59,8 @@ void Copter::init_rc_out()
|
|||||||
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||||
motors.Init(); // motor initialisation
|
motors.Init(); // motor initialisation
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#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_hover_throttle(g.throttle_mid);
|
||||||
|
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
for(uint8_t i = 0; i < 5; i++) {
|
for(uint8_t i = 0; i < 5; i++) {
|
||||||
|
Loading…
Reference in New Issue
Block a user