mirror of https://github.com/ArduPilot/ardupilot
Plane: Quadplane: add `get_throttle_input` method that behaves the same as Plane::get_throttle_input did
This commit is contained in:
parent
483ef18087
commit
41f61da0d9
|
@ -1219,7 +1219,7 @@ bool QuadPlane::is_flying_vtol(void) const
|
|||
}
|
||||
if (plane.control_mode->is_vtol_man_mode()) {
|
||||
// in manual flight modes only consider aircraft landed when pilot demanded throttle is zero
|
||||
return is_positive(plane.get_throttle_input());
|
||||
return is_positive(get_throttle_input());
|
||||
}
|
||||
if (in_vtol_mode() && millis() - landing_detect.lower_limit_start_ms > 5000) {
|
||||
// use landing detector
|
||||
|
@ -1289,7 +1289,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
|||
const auto rudder_in = plane.channel_rudder->get_control_in();
|
||||
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active();
|
||||
if (!manual_air_mode &&
|
||||
!is_positive(plane.get_throttle_input()) &&
|
||||
!is_positive(get_throttle_input()) &&
|
||||
(!plane.control_mode->does_auto_throttle() || motors->limit.throttle_lower) &&
|
||||
plane.arming.get_rudder_arming_type() == AP_Arming::RudderArming::ARMDISARM &&
|
||||
rudder_in < 0 &&
|
||||
|
@ -1366,7 +1366,7 @@ float QuadPlane::get_pilot_desired_climb_rate_cms(void) const
|
|||
*/
|
||||
void QuadPlane::init_throttle_wait(void)
|
||||
{
|
||||
if (plane.get_throttle_input() >= 10 ||
|
||||
if (get_throttle_input() >= 10 ||
|
||||
plane.is_flying()) {
|
||||
throttle_wait = false;
|
||||
} else {
|
||||
|
@ -1920,7 +1920,7 @@ void QuadPlane::update_throttle_suppression(void)
|
|||
consider non-zero throttle to mean that pilot is commanding
|
||||
takeoff unless in a manual thottle mode
|
||||
*/
|
||||
if (!is_zero(plane.get_throttle_input()) &&
|
||||
if (!is_zero(get_throttle_input()) &&
|
||||
(rc().arming_check_throttle() ||
|
||||
plane.control_mode->is_vtol_man_throttle() ||
|
||||
plane.channel_throttle->norm_input_dz() > 0)) {
|
||||
|
@ -4061,7 +4061,7 @@ void QuadPlane::update_throttle_mix(void)
|
|||
|
||||
if (plane.control_mode->is_vtol_man_throttle()) {
|
||||
// manual throttle
|
||||
if (!is_positive(plane.get_throttle_input()) && !air_mode_active()) {
|
||||
if (!is_positive(get_throttle_input()) && !air_mode_active()) {
|
||||
attitude_control->set_throttle_mix_min();
|
||||
} else {
|
||||
attitude_control->set_throttle_mix_man();
|
||||
|
@ -4729,4 +4729,18 @@ bool QuadPlane::should_disable_TECS() const
|
|||
return false;
|
||||
}
|
||||
|
||||
// Get pilot throttle input with deadzone, this will return 50% throttle in failsafe!
|
||||
// This is a re-implmentation of Plane::get_throttle_input
|
||||
// Ignoring the no_deadzone case means we don't need to check for valid RC
|
||||
// This is handled by Plane::control_failsafe setting of control in
|
||||
float QuadPlane::get_throttle_input() const
|
||||
{
|
||||
float ret = plane.channel_throttle->get_control_in();
|
||||
if (plane.reversed_throttle) {
|
||||
// RC option for reverse throttle has been set
|
||||
ret = -ret;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif // HAL_QUADPLANE_ENABLED
|
||||
|
|
|
@ -190,6 +190,9 @@ public:
|
|||
*/
|
||||
bool should_disable_TECS() const;
|
||||
|
||||
// Get pilot throttle input with deadzone, this will return 50% throttle in failsafe!
|
||||
float get_throttle_input() const;
|
||||
|
||||
private:
|
||||
AP_AHRS &ahrs;
|
||||
|
||||
|
|
Loading…
Reference in New Issue