Plane: support REVERSE_THROTTLE rc option

this provides a more convenient way to setup for reverse throttle
This commit is contained in:
Andrew Tridgell 2018-11-10 10:00:20 +11:00
parent 285935f8b3
commit 03f1deca9f
4 changed files with 36 additions and 3 deletions

View File

@ -1065,6 +1065,8 @@ private:
void read_aux_all();
bool reversed_throttle;
bool have_reverse_throttle_rc_option;
bool allow_reverse_thrust(void) const;
bool have_reverse_thrust(void) const;
int16_t get_throttle_input(bool no_deadzone=false) const;

View File

@ -35,7 +35,20 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case ARMDISARM:
case INVERTED:
break;
case REVERSE_THROTTLE:
plane.have_reverse_throttle_rc_option = true;
// setup input throttle as a range. This is needed as init_aux_function is called
// after set_control_channels()
if (plane.channel_throttle) {
plane.channel_throttle->set_range(100);
}
// note that we don't call do_aux_function() here as we don't
// want to startup with reverse thrust
break;
default:
// handle in parent class
RC_Channel::init_aux_function(ch_option, ch_flag);
break;
}
@ -63,6 +76,11 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi
plane.inverted_flight = (ch_flag == HIGH);
break;
case REVERSE_THROTTLE:
plane.reversed_throttle = (ch_flag == HIGH);
gcs().send_text(MAV_SEVERITY_INFO, "RevThrottle: %s", plane.reversed_throttle?"ENABLE":"DISABLE");
break;
default:
RC_Channel::do_aux_function(ch_option, ch_flag);
break;

View File

@ -28,7 +28,13 @@ void Plane::set_control_channels(void)
channel_throttle->set_range(100);
} else {
// reverse thrust
channel_throttle->set_angle(100);
if (have_reverse_throttle_rc_option) {
// when we have a reverse throttle RC option setup we use throttle
// as a range, and rely on the RC switch to get reverse thrust
channel_throttle->set_range(100);
} else {
channel_throttle->set_angle(100);
}
SRV_Channels::set_angle(SRV_Channel::k_throttle, 100);
SRV_Channels::set_angle(SRV_Channel::k_throttleLeft, 100);
SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100);

View File

@ -106,8 +106,15 @@ bool Plane::have_reverse_thrust(void) const
*/
int16_t Plane::get_throttle_input(bool no_deadzone) const
{
int16_t ret;
if (no_deadzone) {
return channel_throttle->get_control_in_zero_dz();
ret = channel_throttle->get_control_in_zero_dz();
} else {
ret = channel_throttle->get_control_in();
}
return channel_throttle->get_control_in();
if (reversed_throttle) {
// RC option for reverse throttle has been set
ret = -ret;
}
return ret;
}