Plane: get throttle input return float

This commit is contained in:
Iampete1 2021-09-18 19:03:54 +01:00 committed by Andrew Tridgell
parent 2f4661c52f
commit b31ce6734a
6 changed files with 16 additions and 16 deletions

View File

@ -174,7 +174,7 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
} }
// if throttle is not down, then pilot cannot rudder arm/disarm // if throttle is not down, then pilot cannot rudder arm/disarm
if (plane.get_throttle_input() != 0){ if (!is_zero(plane.get_throttle_input())){
check_failed(true, "Non-zero throttle"); check_failed(true, "Non-zero throttle");
return false; return false;
} }

View File

@ -520,7 +520,7 @@ void Plane::stabilize()
/* /*
see if we should zero the attitude controller integrators. see if we should zero the attitude controller integrators.
*/ */
if (get_throttle_input() == 0 && if (is_zero(get_throttle_input()) &&
fabsf(relative_altitude) < 5.0f && fabsf(relative_altitude) < 5.0f &&
fabsf(barometer.get_climb_rate()) < 0.5f && fabsf(barometer.get_climb_rate()) < 0.5f &&
ahrs.groundspeed() < 3) { ahrs.groundspeed() < 3) {
@ -616,7 +616,7 @@ void Plane::calc_nav_yaw_course(void)
void Plane::calc_nav_yaw_ground(void) void Plane::calc_nav_yaw_ground(void)
{ {
if (gps.ground_speed() < 1 && if (gps.ground_speed() < 1 &&
get_throttle_input() == 0 && is_zero(get_throttle_input()) &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_TAKEOFF && flight_stage != AP_Vehicle::FixedWing::FLIGHT_TAKEOFF &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { flight_stage != AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
// manual rudder control while still // manual rudder control while still

View File

@ -1110,8 +1110,8 @@ private:
bool have_reverse_throttle_rc_option; bool have_reverse_throttle_rc_option;
bool allow_reverse_thrust(void) const; bool allow_reverse_thrust(void) const;
bool have_reverse_thrust(void) const; bool have_reverse_thrust(void) const;
int16_t get_throttle_input(bool no_deadzone=false) const; float get_throttle_input(bool no_deadzone=false) const;
int16_t get_adjusted_throttle_input(bool no_deadzone=false) const; float get_adjusted_throttle_input(bool no_deadzone=false) const;
enum Failsafe_Action { enum Failsafe_Action {
Failsafe_Action_None = 0, Failsafe_Action_None = 0,

View File

@ -59,7 +59,7 @@ void QuadPlane::motor_test_output()
break; break;
case MOTOR_TEST_THROTTLE_PILOT: case MOTOR_TEST_THROTTLE_PILOT:
pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * (float)plane.get_throttle_input()*0.01f; pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * plane.get_throttle_input()*0.01f;
break; break;
default: default:

View File

@ -1069,7 +1069,7 @@ bool QuadPlane::is_flying_vtol(void) const
} }
if (plane.control_mode->is_vtol_man_mode()) { if (plane.control_mode->is_vtol_man_mode()) {
// in manual flight modes only consider aircraft landed when pilot demanded throttle is zero // in manual flight modes only consider aircraft landed when pilot demanded throttle is zero
return plane.get_throttle_input() > 0; return is_positive(plane.get_throttle_input());
} }
if (in_vtol_mode() && millis() - landing_detect.lower_limit_start_ms > 5000) { if (in_vtol_mode() && millis() - landing_detect.lower_limit_start_ms > 5000) {
// use landing detector // use landing detector
@ -1131,7 +1131,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
{ {
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active();
if (!manual_air_mode && if (!manual_air_mode &&
plane.get_throttle_input() <= 0 && !plane.control_mode->does_auto_throttle() && !is_positive(plane.get_throttle_input()) && !plane.control_mode->does_auto_throttle() &&
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED && !(inertial_nav.get_velocity_z() < -0.5 * get_pilot_velocity_z_max_dn())) { plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED && !(inertial_nav.get_velocity_z() < -0.5 * get_pilot_velocity_z_max_dn())) {
// the user may be trying to disarm // the user may be trying to disarm
return 0; return 0;
@ -1173,7 +1173,7 @@ float QuadPlane::get_desired_yaw_rate_cds(void)
yaw_cds += desired_auto_yaw_rate_cds(); yaw_cds += desired_auto_yaw_rate_cds();
} }
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active();
if (plane.get_throttle_input() <= 0 && !plane.control_mode->does_auto_throttle() && !manual_air_mode && !(inertial_nav.get_velocity_z() < -0.5 * get_pilot_velocity_z_max_dn())) { if (!is_positive(plane.get_throttle_input()) && !plane.control_mode->does_auto_throttle() && !manual_air_mode && !(inertial_nav.get_velocity_z() < -0.5 * get_pilot_velocity_z_max_dn())) {
// the user may be trying to disarm // the user may be trying to disarm
return 0; return 0;
} }
@ -1277,7 +1277,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed)
} }
if (!tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) if (!tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed)
|| plane.get_throttle_input()>0 || is_positive(plane.get_throttle_input())
|| plane.is_flying() ) ) { || plane.is_flying() ) ) {
// not in a flight mode and condition where it would be safe to turn on vertial lift motors // not in a flight mode and condition where it would be safe to turn on vertial lift motors
// skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes
@ -1763,7 +1763,7 @@ void QuadPlane::update_throttle_suppression(void)
} }
// if the users throttle is above zero then allow motors to run // if the users throttle is above zero then allow motors to run
if (plane.get_throttle_input() != 0) { if (!is_zero(plane.get_throttle_input())) {
return; return;
} }
@ -3460,7 +3460,7 @@ void QuadPlane::update_throttle_mix(void)
if (plane.control_mode->is_vtol_man_throttle()) { if (plane.control_mode->is_vtol_man_throttle()) {
// manual throttle // manual throttle
if ((plane.get_throttle_input() <= 0) && !air_mode_active()) { if (!is_positive(plane.get_throttle_input()) && !air_mode_active()) {
attitude_control->set_throttle_mix_min(); attitude_control->set_throttle_mix_min();
} else { } else {
attitude_control->set_throttle_mix_man(); attitude_control->set_throttle_mix_man();

View File

@ -123,9 +123,9 @@ bool Plane::have_reverse_thrust(void) const
/* /*
return control in from the radio throttle channel. return control in from the radio throttle channel.
*/ */
int16_t Plane::get_throttle_input(bool no_deadzone) const float Plane::get_throttle_input(bool no_deadzone) const
{ {
int16_t ret; float ret;
if (no_deadzone) { if (no_deadzone) {
ret = channel_throttle->get_control_in_zero_dz(); ret = channel_throttle->get_control_in_zero_dz();
} else { } else {
@ -141,12 +141,12 @@ int16_t Plane::get_throttle_input(bool no_deadzone) const
/* /*
return control in from the radio throttle channel with curve giving mid-stick equal to TRIM_THROTTLE. return control in from the radio throttle channel with curve giving mid-stick equal to TRIM_THROTTLE.
*/ */
int16_t Plane::get_adjusted_throttle_input(bool no_deadzone) const float Plane::get_adjusted_throttle_input(bool no_deadzone) const
{ {
if ((plane.channel_throttle->get_type() != RC_Channel::RC_CHANNEL_TYPE_RANGE) || (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) == 0) { if ((plane.channel_throttle->get_type() != RC_Channel::RC_CHANNEL_TYPE_RANGE) || (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) == 0) {
return get_throttle_input(no_deadzone); return get_throttle_input(no_deadzone);
} }
int16_t ret = channel_throttle->get_range() * throttle_curve(aparm.throttle_cruise * 0.01, 0, 0.5 + 0.5*channel_throttle->norm_input()); float ret = channel_throttle->get_range() * throttle_curve(aparm.throttle_cruise * 0.01, 0, 0.5 + 0.5*channel_throttle->norm_input());
if (reversed_throttle) { if (reversed_throttle) {
// RC option for reverse throttle has been set // RC option for reverse throttle has been set
return -ret; return -ret;