2018-04-26 22:01:37 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
|
|
|
#include "RC_Channel.h"
|
|
|
|
|
|
|
|
// defining these two macros and including the RC_Channels_VarInfo
|
|
|
|
// header defines the parameter information common to all vehicle
|
|
|
|
// types
|
|
|
|
#define RC_CHANNELS_SUBCLASS RC_Channels_Plane
|
|
|
|
#define RC_CHANNEL_SUBCLASS RC_Channel_Plane
|
|
|
|
|
|
|
|
#include <RC_Channel/RC_Channels_VarInfo.h>
|
|
|
|
|
|
|
|
// note that this callback is not presently used on Plane:
|
|
|
|
int8_t RC_Channels_Plane::flight_mode_channel_number() const
|
|
|
|
{
|
|
|
|
return plane.g.flight_mode_channel.get();
|
|
|
|
}
|
2018-08-03 06:56:58 -03:00
|
|
|
|
|
|
|
bool RC_Channels_Plane::has_valid_input() const
|
|
|
|
{
|
|
|
|
if (plane.failsafe.rc_failsafe) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (plane.failsafe.throttle_counter != 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
2018-09-05 01:22:14 -03:00
|
|
|
|
|
|
|
void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
|
|
|
const RC_Channel::aux_switch_pos_t ch_flag)
|
|
|
|
{
|
|
|
|
switch(ch_option) {
|
|
|
|
// the following functions do not need to be initialised:
|
|
|
|
case ARMDISARM:
|
2018-08-11 08:12:35 -03:00
|
|
|
case INVERTED:
|
2018-09-05 01:22:14 -03:00
|
|
|
break;
|
2018-11-09 19:00:20 -04:00
|
|
|
|
|
|
|
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;
|
|
|
|
|
2018-09-05 01:22:14 -03:00
|
|
|
default:
|
2018-11-09 19:00:20 -04:00
|
|
|
// handle in parent class
|
2018-09-05 01:22:14 -03:00
|
|
|
RC_Channel::init_aux_function(ch_option, ch_flag);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// do_aux_function - implement the function invoked by auxillary switches
|
|
|
|
void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
|
|
|
{
|
|
|
|
switch(ch_option) {
|
|
|
|
case ARMDISARM:
|
|
|
|
// arm or disarm the vehicle
|
|
|
|
switch (ch_flag) {
|
|
|
|
case HIGH:
|
|
|
|
plane.arm_motors(AP_Arming::ArmingMethod::AUXSWITCH, true);
|
|
|
|
break;
|
|
|
|
case MIDDLE:
|
|
|
|
// nothing
|
|
|
|
break;
|
|
|
|
case LOW:
|
|
|
|
plane.disarm_motors();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
2018-08-11 08:12:35 -03:00
|
|
|
case INVERTED:
|
|
|
|
plane.inverted_flight = (ch_flag == HIGH);
|
|
|
|
break;
|
2018-06-10 03:33:06 -03:00
|
|
|
|
2018-11-09 19:00:20 -04:00
|
|
|
case REVERSE_THROTTLE:
|
|
|
|
plane.reversed_throttle = (ch_flag == HIGH);
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "RevThrottle: %s", plane.reversed_throttle?"ENABLE":"DISABLE");
|
|
|
|
break;
|
|
|
|
|
2018-09-05 01:22:14 -03:00
|
|
|
default:
|
|
|
|
RC_Channel::do_aux_function(ch_option, ch_flag);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|