RC_Channel: move handling of auxillary switches into RC_Channel
RC_Channel: move handling of Rover's functions into RC_Channel RC_Channel: move auxsw handling for camera to base RC_Channel RC_Channel: add responsibility for servorelay events RC_Channel: move mode switch handling to base class
This commit is contained in:
parent
007434cdac
commit
61c34ea98c
@ -27,6 +27,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#include "RC_Channel.h"
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
uint32_t RC_Channel::configured_mask;
|
||||
|
||||
const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||
@ -72,6 +74,14 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DZ", 5, RC_Channel, dead_zone, 0),
|
||||
|
||||
// @Param: OPTION
|
||||
// @DisplayName: RC input option
|
||||
// @Description: Function assigned to this RC channel
|
||||
// @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3
|
||||
// @Values{Rover}: 0:Do Nothing, 4:RTL, 7:Save WP, 9:Camera Trigger, 16:Auto, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 42:SmartRTL, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -343,3 +353,220 @@ bool RC_Channel::min_max_configured() const
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
//
|
||||
// support for auxillary switches:
|
||||
//
|
||||
#define MODE_SWITCH_DEBOUNCE_TIME_MS 200
|
||||
|
||||
uint32_t RC_Channel::old_switch_positions;
|
||||
RC_Channel::modeswitch_state_t RC_Channel::mode_switch_state;
|
||||
|
||||
void RC_Channel::reset_mode_switch()
|
||||
{
|
||||
mode_switch_state.last_position = -1;
|
||||
mode_switch_state.debounced_position = -1;
|
||||
read_mode_switch();
|
||||
}
|
||||
|
||||
void RC_Channel::read_mode_switch()
|
||||
{
|
||||
// calculate position of flight mode switch
|
||||
const uint16_t pulsewidth = get_radio_in();
|
||||
if (pulsewidth <= 900 || pulsewidth >= 2200) {
|
||||
return; // This is an error condition
|
||||
}
|
||||
|
||||
modeswitch_pos_t position;
|
||||
if (pulsewidth < 1231) position = 0;
|
||||
else if (pulsewidth < 1361) position = 1;
|
||||
else if (pulsewidth < 1491) position = 2;
|
||||
else if (pulsewidth < 1621) position = 3;
|
||||
else if (pulsewidth < 1750) position = 4;
|
||||
else position = 5;
|
||||
|
||||
if (mode_switch_state.last_position == position) {
|
||||
// nothing to do
|
||||
return;
|
||||
}
|
||||
|
||||
const uint32_t tnow_ms = AP_HAL::millis();
|
||||
if (position != mode_switch_state.debounced_position) {
|
||||
mode_switch_state.debounced_position = position;
|
||||
// store time that switch last moved
|
||||
mode_switch_state.last_edge_time_ms = tnow_ms;
|
||||
return;
|
||||
}
|
||||
|
||||
if (tnow_ms - mode_switch_state.last_edge_time_ms < MODE_SWITCH_DEBOUNCE_TIME_MS) {
|
||||
// still in debounce
|
||||
return;
|
||||
}
|
||||
|
||||
// set flight mode and simple mode setting
|
||||
mode_switch_changed(position);
|
||||
|
||||
// set the last switch position. This marks the
|
||||
// transition as complete, even if the mode switch actually
|
||||
// failed. This prevents the vehicle changing modes
|
||||
// unexpectedly some time later.
|
||||
mode_switch_state.last_position = position;
|
||||
}
|
||||
|
||||
//
|
||||
// support for auxillary switches:
|
||||
//
|
||||
|
||||
// init_aux_switch_function - initialize aux functions
|
||||
void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
// init channel options
|
||||
switch(ch_option) {
|
||||
// the following functions to not need to be initialised:
|
||||
case RELAY:
|
||||
case RELAY2:
|
||||
case RELAY3:
|
||||
case RELAY4:
|
||||
case CAMERA_TRIGGER:
|
||||
case DO_NOTHING:
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", ch_option);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::read_aux()
|
||||
{
|
||||
const aux_func_t _option = (aux_func_t)option.get();
|
||||
if (_option == DO_NOTHING) {
|
||||
// may wish to add special cases for other "AUXSW" things
|
||||
// here e.g. RCMAP_ROLL etc once they become options
|
||||
return;
|
||||
}
|
||||
const aux_switch_pos_t new_position = read_3pos_switch();
|
||||
const aux_switch_pos_t old_position = old_switch_position();
|
||||
if (new_position == old_position) {
|
||||
debounce.count = 0;
|
||||
return;
|
||||
}
|
||||
if (debounce.new_position != new_position) {
|
||||
debounce.new_position = new_position;
|
||||
debounce.count = 0;
|
||||
}
|
||||
// a value of 2 means we need 3 values in a row with the same
|
||||
// value to activate
|
||||
if (debounce.count++ < 2) {
|
||||
return;
|
||||
}
|
||||
|
||||
// debounced; undertake the action:
|
||||
do_aux_function(_option, new_position);
|
||||
set_old_switch_position(new_position);
|
||||
}
|
||||
|
||||
|
||||
void RC_Channel::do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
return;
|
||||
}
|
||||
if (ch_flag == HIGH) {
|
||||
camera->take_picture();
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::do_aux_function_relay(const uint8_t relay, bool val)
|
||||
{
|
||||
AP_ServoRelayEvents *servorelayevents = AP::servorelayevents();
|
||||
if (servorelayevents == nullptr) {
|
||||
return;
|
||||
}
|
||||
servorelayevents->do_set_relay(relay, val);
|
||||
}
|
||||
|
||||
void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
switch(ch_option) {
|
||||
case CAMERA_TRIGGER:
|
||||
do_aux_function_camera_trigger(ch_flag);
|
||||
break;
|
||||
|
||||
case RELAY:
|
||||
do_aux_function_relay(0, ch_flag == HIGH);
|
||||
break;
|
||||
case RELAY2:
|
||||
do_aux_function_relay(1, ch_flag == HIGH);
|
||||
break;
|
||||
case RELAY3:
|
||||
do_aux_function_relay(2, ch_flag == HIGH);
|
||||
break;
|
||||
case RELAY4:
|
||||
do_aux_function_relay(3, ch_flag == HIGH);
|
||||
break;
|
||||
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", ch_option);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::init_aux()
|
||||
{
|
||||
const aux_switch_pos_t position = read_3pos_switch();
|
||||
set_old_switch_position(position);
|
||||
init_aux_function((aux_func_t)option.get(), position);
|
||||
}
|
||||
|
||||
// read_3pos_switch
|
||||
RC_Channel::aux_switch_pos_t RC_Channel::read_3pos_switch() const
|
||||
{
|
||||
const uint16_t in = get_radio_in();
|
||||
if (in < AUX_PWM_TRIGGER_LOW) return LOW; // switch is in low position
|
||||
if (in > AUX_PWM_TRIGGER_HIGH) return HIGH; // switch is in high position
|
||||
return MIDDLE; // switch is in middle position
|
||||
}
|
||||
|
||||
RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
|
||||
{
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
RC_Channel *c = channel(i);
|
||||
if (c == nullptr) {
|
||||
// odd?
|
||||
continue;
|
||||
}
|
||||
if ((RC_Channel::aux_func_t)c->option.get() == option) {
|
||||
return c;
|
||||
}
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// duplicate_options_exist - returns true if any options are duplicated
|
||||
bool RC_Channels::duplicate_options_exist()
|
||||
{
|
||||
uint8_t auxsw_option_counts[256] = {};
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
const RC_Channel *c = channel(i);
|
||||
if (c == nullptr) {
|
||||
// odd?
|
||||
continue;
|
||||
}
|
||||
const uint16_t option = c->option.get();
|
||||
if (option > sizeof(auxsw_option_counts)) {
|
||||
continue;
|
||||
}
|
||||
auxsw_option_counts[option]++;
|
||||
}
|
||||
|
||||
for (uint16_t i=0; i<sizeof(auxsw_option_counts); i++) {
|
||||
if (i == 0) { // MAGIC VALUE! This is AUXSW_DO_NOTHING
|
||||
continue;
|
||||
}
|
||||
if (auxsw_option_counts[i] > 1) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -100,6 +100,96 @@ public:
|
||||
|
||||
bool min_max_configured() const;
|
||||
|
||||
AP_Int16 option; // e.g. activate EPM gripper / enable fence
|
||||
|
||||
// auxillary switch support:
|
||||
void init_aux();
|
||||
void read_aux();
|
||||
|
||||
// Aux Switch enumeration
|
||||
enum aux_func {
|
||||
DO_NOTHING = 0, // aux switch disabled
|
||||
FLIP = 2, // flip
|
||||
SIMPLE_MODE = 3, // change to simple mode
|
||||
RTL = 4, // change to RTL flight mode
|
||||
SAVE_TRIM = 5, // save current position as level
|
||||
SAVE_WP = 7, // save mission waypoint or RTL if in auto mode
|
||||
CAMERA_TRIGGER = 9, // trigger camera servo or relay
|
||||
RANGEFINDER = 10, // allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground
|
||||
FENCE = 11, // allow enabling or disabling fence in flight
|
||||
RESETTOARMEDYAW = 12, // UNUSED
|
||||
SUPERSIMPLE_MODE = 13, // change to simple mode in middle, super simple at top
|
||||
ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
|
||||
SPRAYER = 15, // enable/disable the crop sprayer
|
||||
AUTO = 16, // change to auto flight mode
|
||||
AUTOTUNE = 17, // auto tune
|
||||
LAND = 18, // change to LAND flight mode
|
||||
GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
|
||||
PARACHUTE_ENABLE = 21, // Parachute enable/disable
|
||||
PARACHUTE_RELEASE = 22, // Parachute release
|
||||
PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
|
||||
MISSION_RESET = 24, // Reset auto mission to start from first command
|
||||
ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward
|
||||
ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting
|
||||
RETRACT_MOUNT = 27, // Retract Mount
|
||||
RELAY = 28, // Relay pin on/off (only supports first relay)
|
||||
LANDING_GEAR = 29, // Landing gear controller
|
||||
LOST_COPTER_SOUND = 30, // Play lost copter sound
|
||||
MOTOR_ESTOP = 31, // Emergency Stop Switch
|
||||
MOTOR_INTERLOCK = 32, // Motor On/Off switch
|
||||
BRAKE = 33, // Brake flight mode
|
||||
RELAY2 = 34, // Relay2 pin on/off (in Mission planner set RC8_OPTION = 34)
|
||||
RELAY3 = 35, // Relay3 pin on/off (in Mission planner set RC9_OPTION = 35)
|
||||
RELAY4 = 36, // Relay4 pin on/off (in Mission planner set RC10_OPTION = 36)
|
||||
THROW = 37, // change to THROW flight mode
|
||||
AVOID_ADSB = 38, // enable AP_Avoidance library
|
||||
PRECISION_LOITER = 39, // enable precision loiter
|
||||
AVOID_PROXIMITY = 40, // enable object avoidance using proximity sensors (ie. horizontal lidar)
|
||||
ARMDISARM = 41, // arm or disarm vehicle
|
||||
SMART_RTL = 42, // change to SmartRTL flight mode
|
||||
INVERTED = 43, // enable inverted flight
|
||||
WINCH_ENABLE = 44, // winch enable/disable
|
||||
WINCH_CONTROL = 45, // winch control
|
||||
RC_OVERRIDE_ENABLE = 46, // enable RC Override
|
||||
USER_FUNC1 = 47, // user function #1
|
||||
USER_FUNC2 = 48, // user function #2
|
||||
USER_FUNC3 = 49, // user function #3
|
||||
LEARN_CRUISE = 50, // learn cruise throttle (Rover)
|
||||
MANUAL = 51, // manual mode
|
||||
ACRO = 52, // acro mode
|
||||
STEERING = 53, // steering mode
|
||||
HOLD = 54, // hold mode
|
||||
GUIDED = 55, // guided mode
|
||||
LOITER = 56, // loiter mode
|
||||
FOLLOW = 57, // follow mode
|
||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
||||
};
|
||||
typedef enum aux_func aux_func_t;
|
||||
|
||||
protected:
|
||||
|
||||
// auxillary switch handling:
|
||||
enum aux_switch_pos {
|
||||
LOW, // indicates auxiliary switch is in the low position (pwm <1200)
|
||||
MIDDLE, // indicates auxiliary switch is in the middle position (pwm >1200, <1800)
|
||||
HIGH // indicates auxiliary switch is in the high position (pwm >1800)
|
||||
};
|
||||
|
||||
typedef enum aux_switch_pos aux_switch_pos_t;
|
||||
|
||||
virtual void init_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
virtual void do_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
|
||||
void do_aux_function_relay(uint8_t relay, bool val);
|
||||
void do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag);
|
||||
|
||||
typedef int8_t modeswitch_pos_t;
|
||||
virtual void mode_switch_changed(modeswitch_pos_t new_pos) {
|
||||
// no action by default (e.g. Tracker, Sub, who do their own thing)
|
||||
};
|
||||
|
||||
|
||||
private:
|
||||
|
||||
// pwm is stored here
|
||||
@ -130,6 +220,44 @@ private:
|
||||
|
||||
int16_t pwm_to_angle();
|
||||
int16_t pwm_to_angle_dz(uint16_t dead_zone);
|
||||
|
||||
// pwm value above which the option will be invoked:
|
||||
static const uint16_t AUX_PWM_TRIGGER_HIGH = 1800;
|
||||
// pwm value below which the option will be disabled:
|
||||
static const uint16_t AUX_PWM_TRIGGER_LOW = 1200;
|
||||
aux_switch_pos_t read_3pos_switch() const;
|
||||
|
||||
//Documentation of Aux Switch Flags:
|
||||
// 0 is low or false, 1 is center or true, 2 is high
|
||||
// pairs of bits in old_switch_positions give the old switch position for an RC input.
|
||||
static uint32_t old_switch_positions;
|
||||
|
||||
aux_switch_pos_t old_switch_position() const {
|
||||
return (aux_switch_pos_t)((old_switch_positions >> (ch_in*2)) & 0x3);
|
||||
}
|
||||
void set_old_switch_position(const RC_Channel::aux_switch_pos_t value) {
|
||||
old_switch_positions &= ~(0x3 << (ch_in*2));
|
||||
old_switch_positions |= (value << (ch_in*2));
|
||||
}
|
||||
|
||||
// Structure used to detect changes in the flight mode control switch
|
||||
// static since we should only ever have one mode switch!
|
||||
typedef struct {
|
||||
modeswitch_pos_t debounced_position; // currently used position
|
||||
modeswitch_pos_t last_position; // position in previous iteration
|
||||
uint32_t last_edge_time_ms; // system time that position was last changed
|
||||
} modeswitch_state_t;
|
||||
static modeswitch_state_t mode_switch_state;
|
||||
|
||||
// de-bounce counters
|
||||
typedef struct {
|
||||
uint8_t count;
|
||||
uint8_t new_position;
|
||||
} debounce_state_t;
|
||||
debounce_state_t debounce;
|
||||
|
||||
void reset_mode_switch();
|
||||
void read_mode_switch();
|
||||
};
|
||||
|
||||
|
||||
@ -143,31 +271,56 @@ public:
|
||||
// constructor
|
||||
RC_Channels(void);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
void init(void);
|
||||
|
||||
static RC_Channel *rc_channel(uint8_t chan) {
|
||||
return (chan < NUM_RC_CHANNELS)?&channels[chan]:nullptr;
|
||||
// get singleton instance
|
||||
static RC_Channels *get_singleton() {
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
static uint16_t get_radio_in(const uint8_t chan); // returns the last read radio_in value from a chan, 0 if the channel is out of range
|
||||
static uint8_t get_radio_in(uint16_t *chans, const uint8_t num_channels); // reads a block of chanel radio_in values starting from channel 0
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
virtual RC_Channel *channel(uint8_t chan) = 0;
|
||||
|
||||
uint8_t get_radio_in(uint16_t *chans, const uint8_t num_channels); // reads a block of chanel radio_in values starting from channel 0
|
||||
// returns the number of valid channels
|
||||
|
||||
static uint8_t get_valid_channel_count(void); // returns the number of valid channels in the last read
|
||||
static int16_t get_receiver_rssi(void); // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1
|
||||
static bool read_input(void); // returns true if new input has been read in
|
||||
bool read_input(void); // returns true if new input has been read in
|
||||
static void clear_overrides(void); // clears any active overrides
|
||||
static bool receiver_bind(const int dsmMode); // puts the reciever in bind mode if present, returns true if success
|
||||
static void set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms = 0); // set a channels override value
|
||||
static bool has_active_overrides(void); // returns true if there are overrides applied that are valid
|
||||
|
||||
class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
|
||||
bool duplicate_options_exist();
|
||||
|
||||
void init_aux_all();
|
||||
virtual void read_aux_all();
|
||||
|
||||
// mode switch handling
|
||||
void reset_mode_switch();
|
||||
virtual void read_mode_switch();
|
||||
|
||||
virtual bool in_rc_failsafe() const = 0;
|
||||
|
||||
private:
|
||||
static RC_Channels *_singleton;
|
||||
// this static arrangement is to avoid static pointers in AP_Param tables
|
||||
static RC_Channel *channels;
|
||||
|
||||
static bool has_new_overrides;
|
||||
static AP_Float *override_timeout;
|
||||
static AP_Int32 *options;
|
||||
RC_Channel obj_channels[NUM_RC_CHANNELS];
|
||||
AP_Float _override_timeout;
|
||||
AP_Int32 _options;
|
||||
|
||||
// flight_mode_channel_number must be overridden:
|
||||
virtual int8_t flight_mode_channel_number() const = 0;
|
||||
RC_Channel *flight_mode_channel();
|
||||
|
||||
};
|
||||
|
||||
RC_Channels &rc();
|
||||
|
@ -33,90 +33,6 @@ bool RC_Channels::has_new_overrides;
|
||||
AP_Float *RC_Channels::override_timeout;
|
||||
AP_Int32 *RC_Channels::options;
|
||||
|
||||
const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
||||
// @Group: 1_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[0], "1_", 1, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 2_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[1], "2_", 2, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 3_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[2], "3_", 3, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 4_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[3], "4_", 4, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 5_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[4], "5_", 5, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 6_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[5], "6_", 6, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 7_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[6], "7_", 7, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 8_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[7], "8_", 8, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 9_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[8], "9_", 9, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 10_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[9], "10_", 10, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 11_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[10], "11_", 11, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 12_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[11], "12_", 12, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 13_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[12], "13_", 13, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 14_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[13], "14_", 14, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 15_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[14], "15_", 15, RC_Channels, RC_Channel),
|
||||
|
||||
// @Group: 16_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[15], "16_", 16, RC_Channels, RC_Channel),
|
||||
|
||||
// @Param: _OVERRIDE_TIME
|
||||
// @DisplayName: RC override timeout
|
||||
// @Description: Timeout after which RC overrides will no longer be used, and RC input will resume, 0 will disable RC overrides, -1 will never timeout, and continue using overrides until they are disabled
|
||||
// @User: Advanced
|
||||
// @Range: 0.0 120.0
|
||||
// @Units: s
|
||||
AP_GROUPINFO("_OVERRIDE_TIME", 32, RC_Channels, _override_timeout, 3.0),
|
||||
|
||||
// @Param: _OPTIONS
|
||||
// @DisplayName: RC options
|
||||
// @Description: RC input options
|
||||
// @User: Advanced
|
||||
// @Bitmask: 0:Ignore RC Reciever, 1:Ignore MAVLink Overrides
|
||||
AP_GROUPINFO("_OPTIONS", 33, RC_Channels, _options, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
channels group object constructor
|
||||
*/
|
||||
@ -126,29 +42,31 @@ RC_Channels::RC_Channels(void)
|
||||
|
||||
override_timeout = &_override_timeout;
|
||||
options = &_options;
|
||||
|
||||
|
||||
// set defaults from the parameter table
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// setup ch_in on channels
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
channels[i].ch_in = i;
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("RC_Channels must be singleton");
|
||||
}
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
uint16_t RC_Channels::get_radio_in(const uint8_t chan)
|
||||
void RC_Channels::init(void)
|
||||
{
|
||||
if (chan >= NUM_RC_CHANNELS) {
|
||||
return 0;
|
||||
// setup ch_in on channels
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
channel(i)->ch_in = i;
|
||||
}
|
||||
return channels[chan].get_radio_in();
|
||||
|
||||
init_aux_all();
|
||||
}
|
||||
|
||||
uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
|
||||
{
|
||||
uint8_t read_channels = MIN(num_channels, NUM_RC_CHANNELS);
|
||||
const uint8_t read_channels = MIN(num_channels, NUM_RC_CHANNELS);
|
||||
for (uint8_t i = 0; i < read_channels; i++) {
|
||||
chans[i] = channels[i].get_radio_in();
|
||||
chans[i] = channel(i)->get_radio_in();
|
||||
}
|
||||
|
||||
// clear any excess channels we couldn't read
|
||||
@ -160,8 +78,7 @@ uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
|
||||
}
|
||||
|
||||
// update all the input channels
|
||||
bool
|
||||
RC_Channels::read_input(void)
|
||||
bool RC_Channels::read_input(void)
|
||||
{
|
||||
if (!hal.rcin->new_input() && !has_new_overrides) {
|
||||
return false;
|
||||
@ -171,7 +88,7 @@ RC_Channels::read_input(void)
|
||||
|
||||
bool success = false;
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
success |= channels[i].update();
|
||||
success |= channel(i)->update();
|
||||
}
|
||||
|
||||
return success;
|
||||
@ -220,3 +137,80 @@ bool RC_Channels::receiver_bind(const int dsmMode)
|
||||
{
|
||||
return hal.rcin->rc_bind(dsmMode);
|
||||
}
|
||||
|
||||
|
||||
// support for auxillary switches:
|
||||
// read_aux_switches - checks aux switch positions and invokes configured actions
|
||||
void RC_Channels::read_aux_all()
|
||||
{
|
||||
if (in_rc_failsafe()) {
|
||||
// exit immediately during radio failsafe
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
RC_Channel *c = channel(i);
|
||||
if (c == nullptr) {
|
||||
continue;
|
||||
}
|
||||
c->read_aux();
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channels::init_aux_all()
|
||||
{
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
RC_Channel *c = channel(i);
|
||||
if (c == nullptr) {
|
||||
continue;
|
||||
}
|
||||
c->init_aux();
|
||||
}
|
||||
reset_mode_switch();
|
||||
}
|
||||
|
||||
//
|
||||
// Support for mode switches
|
||||
//
|
||||
RC_Channel *RC_Channels::flight_mode_channel()
|
||||
{
|
||||
const int8_t num = flight_mode_channel_number();
|
||||
if (num <= 0) {
|
||||
return nullptr;
|
||||
}
|
||||
if (num >= NUM_RC_CHANNELS) {
|
||||
return nullptr;
|
||||
}
|
||||
return channel(num-1);
|
||||
}
|
||||
|
||||
void RC_Channels::reset_mode_switch()
|
||||
{
|
||||
RC_Channel *c = flight_mode_channel();
|
||||
if (c == nullptr) {
|
||||
return;
|
||||
}
|
||||
c->reset_mode_switch();
|
||||
}
|
||||
|
||||
void RC_Channels::read_mode_switch()
|
||||
{
|
||||
if (in_rc_failsafe()) {
|
||||
return;
|
||||
}
|
||||
RC_Channel *c = flight_mode_channel();
|
||||
if (c == nullptr) {
|
||||
return;
|
||||
}
|
||||
c->read_mode_switch();
|
||||
}
|
||||
|
||||
|
||||
// singleton instance
|
||||
RC_Channels *RC_Channels::_singleton;
|
||||
|
||||
|
||||
RC_Channels &rc()
|
||||
{
|
||||
return *RC_Channels::get_singleton();
|
||||
}
|
||||
|
93
libraries/RC_Channel/RC_Channels_VarInfo.h
Normal file
93
libraries/RC_Channel/RC_Channels_VarInfo.h
Normal file
@ -0,0 +1,93 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
this header file is expected to be #included by Vehicle subclasses
|
||||
of RC_Channels after defining RC_CHANNELS_SUBCLASS and
|
||||
RC_CHANNEL_SUBCLASS - for example, Rover defines
|
||||
RC_CHANNELS_SUBCLASS to be RC_Channels_Rover in APMrover2/RC_Channels.cpp, and then includes this header.
|
||||
|
||||
This scheme reduces code duplicate between the Vehicles, and avoids the chance of things getting out of sync.
|
||||
*/
|
||||
|
||||
const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
||||
// @Group: 1_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[0], "1_", 1, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 2_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[1], "2_", 2, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 3_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[2], "3_", 3, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 4_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[3], "4_", 4, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 5_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[4], "5_", 5, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 6_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[5], "6_", 6, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 7_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[6], "7_", 7, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 8_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[7], "8_", 8, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 9_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[8], "9_", 9, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 10_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[9], "10_", 10, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 11_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[10], "11_", 11, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 12_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[11], "12_", 12, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 13_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[12], "13_", 13, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 14_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[13], "14_", 14, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 15_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[14], "15_", 15, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Group: 16_
|
||||
// @Path: RC_Channel.cpp
|
||||
AP_SUBGROUPINFO(obj_channels[15], "16_", 16, RC_CHANNELS_SUBCLASS, RC_CHANNEL_SUBCLASS),
|
||||
|
||||
// @Param: _OVERRIDE_TIME
|
||||
// @DisplayName: RC override timeout
|
||||
// @Description: Timeout after which RC overrides will no longer be used, and RC input will resume, 0 will disable RC overrides, -1 will never timeout, and continue using overrides until they are disabled
|
||||
// @User: Advanced
|
||||
// @Range: 0.0 120.0
|
||||
// @Units: s
|
||||
AP_GROUPINFO("_OVERRIDE_TIME", 32, RC_CHANNELS_SUBCLASS, _override_timeout, 3.0),
|
||||
|
||||
// @Param: _OPTIONS
|
||||
// @DisplayName: RC options
|
||||
// @Description: RC input options
|
||||
// @User: Advanced
|
||||
// @Bitmask: 0:Ignore RC Reciever, 1:Ignore MAVLink Overrides
|
||||
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
Loading…
Reference in New Issue
Block a user