2010-11-28 03:03:23 -04:00
|
|
|
/// @file RC_Channel.h
|
|
|
|
/// @brief RC_Channel manager, with EEPROM-backed storage of constants.
|
2016-02-17 21:25:57 -04:00
|
|
|
#pragma once
|
2010-11-23 15:28:19 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2012-10-26 20:59:16 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
#define NUM_RC_CHANNELS 16
|
2013-08-17 22:37:42 -03:00
|
|
|
|
2010-11-28 03:03:23 -04:00
|
|
|
/// @class RC_Channel
|
|
|
|
/// @brief Object managing one RC channel
|
2012-08-17 03:22:48 -03:00
|
|
|
class RC_Channel {
|
|
|
|
public:
|
2017-01-08 20:47:26 -04:00
|
|
|
friend class SRV_Channels;
|
2016-10-22 07:27:40 -03:00
|
|
|
friend class RC_Channels;
|
|
|
|
// Constructor
|
|
|
|
RC_Channel(void);
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2018-09-01 21:01:11 -03:00
|
|
|
enum ChannelType {
|
|
|
|
RC_CHANNEL_TYPE_ANGLE = 0,
|
|
|
|
RC_CHANNEL_TYPE_RANGE = 1,
|
|
|
|
};
|
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
// setup the control preferences
|
2016-10-22 07:27:40 -03:00
|
|
|
void set_range(uint16_t high);
|
2018-09-01 21:01:11 -03:00
|
|
|
uint16_t get_range() const { return high_in; }
|
2016-10-22 07:27:40 -03:00
|
|
|
void set_angle(uint16_t angle);
|
2014-04-20 21:34:10 -03:00
|
|
|
bool get_reverse(void) const;
|
2013-07-11 11:08:16 -03:00
|
|
|
void set_default_dead_zone(int16_t dzone);
|
2016-10-22 07:27:40 -03:00
|
|
|
uint16_t get_dead_zone(void) const { return dead_zone; }
|
2018-12-05 04:29:49 -04:00
|
|
|
|
2014-11-17 18:00:31 -04:00
|
|
|
// get the center stick position expressed as a control_in value
|
2014-11-17 20:18:51 -04:00
|
|
|
int16_t get_control_mid() const;
|
2014-11-17 18:00:31 -04:00
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// read input from hal.rcin - create a control_in value
|
2018-07-24 22:50:01 -03:00
|
|
|
bool update(void);
|
2018-04-10 19:50:16 -03:00
|
|
|
void recompute_pwm_no_deadzone();
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// calculate an angle given dead_zone and trim. This is used by the quadplane code
|
|
|
|
// for hover throttle
|
2018-10-12 19:56:44 -03:00
|
|
|
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim) const;
|
2014-11-17 21:44:05 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a normalised input for a channel, in range -1 to 1,
|
|
|
|
centered around the channel trim. Ignore deadzone.
|
|
|
|
*/
|
2018-10-12 19:56:44 -03:00
|
|
|
float norm_input() const;
|
2014-11-17 21:44:05 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a normalised input for a channel, in range -1 to 1,
|
|
|
|
centered around the channel trim. Take into account the deadzone
|
|
|
|
*/
|
2018-10-12 19:56:44 -03:00
|
|
|
float norm_input_dz() const;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2018-10-12 19:56:44 -03:00
|
|
|
uint8_t percent_input() const;
|
|
|
|
int16_t pwm_to_range() const;
|
|
|
|
int16_t pwm_to_range_dz(uint16_t dead_zone) const;
|
2017-01-07 01:37:00 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// return true if input is within deadzone of trim
|
2018-10-12 19:56:44 -03:00
|
|
|
bool in_trim_dz() const;
|
2016-10-22 07:27:40 -03:00
|
|
|
|
|
|
|
int16_t get_radio_in() const { return radio_in;}
|
|
|
|
void set_radio_in(int16_t val) {radio_in = val;}
|
|
|
|
|
|
|
|
int16_t get_control_in() const { return control_in;}
|
|
|
|
void set_control_in(int16_t val) { control_in = val;}
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
void clear_override();
|
2018-08-02 23:23:53 -03:00
|
|
|
void set_override(const uint16_t v, const uint32_t timestamp_us);
|
2018-04-25 23:06:19 -03:00
|
|
|
bool has_override() const;
|
|
|
|
|
2019-05-01 17:43:27 -03:00
|
|
|
int16_t stick_mixing(const int16_t servo_in);
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// get control input with zero deadzone
|
2019-01-21 01:46:55 -04:00
|
|
|
int16_t get_control_in_zero_dz(void) const;
|
2018-12-05 04:29:49 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t get_radio_min() const {return radio_min.get();}
|
|
|
|
void set_radio_min(int16_t val) { radio_min = val;}
|
|
|
|
|
|
|
|
int16_t get_radio_max() const {return radio_max.get();}
|
|
|
|
void set_radio_max(int16_t val) {radio_max = val;}
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t get_radio_trim() const { return radio_trim.get();}
|
|
|
|
void set_radio_trim(int16_t val) { radio_trim.set(val);}
|
|
|
|
void save_radio_trim() { radio_trim.save();}
|
2013-06-03 02:11:17 -03:00
|
|
|
|
2017-07-01 19:46:06 -03:00
|
|
|
void set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);}
|
2018-01-05 21:51:04 -04:00
|
|
|
|
|
|
|
// set and save trim if changed
|
|
|
|
void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
|
2018-08-04 04:06:21 -03:00
|
|
|
|
2018-09-01 21:01:11 -03:00
|
|
|
ChannelType get_type(void) const { return type_in; }
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
AP_Int16 option; // e.g. activate EPM gripper / enable fence
|
|
|
|
|
|
|
|
// auxillary switch support:
|
|
|
|
void init_aux();
|
2019-05-20 21:41:52 -03:00
|
|
|
bool read_aux();
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
// Aux Switch enumeration
|
2019-04-03 10:23:06 -03:00
|
|
|
enum class AUX_FUNC {
|
2018-04-13 23:22:14 -03:00
|
|
|
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
|
2018-08-27 05:15:51 -03:00
|
|
|
LOST_VEHICLE_SOUND = 30, // Play lost vehicle sound
|
2018-04-13 23:22:14 -03:00
|
|
|
MOTOR_ESTOP = 31, // Emergency Stop Switch
|
|
|
|
MOTOR_INTERLOCK = 32, // Motor On/Off switch
|
|
|
|
BRAKE = 33, // Brake flight mode
|
2018-10-20 18:54:00 -03:00
|
|
|
RELAY2 = 34, // Relay2 pin on/off
|
|
|
|
RELAY3 = 35, // Relay3 pin on/off
|
|
|
|
RELAY4 = 36, // Relay4 pin on/off
|
2018-10-25 04:19:04 -03:00
|
|
|
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
|
2018-04-13 23:22:14 -03:00
|
|
|
SMART_RTL = 42, // change to SmartRTL flight mode
|
2018-10-25 04:19:04 -03:00
|
|
|
INVERTED = 43, // enable inverted flight
|
2018-04-13 23:22:14 -03:00
|
|
|
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
|
2018-08-16 23:44:15 -03:00
|
|
|
CLEAR_WP = 58, // clear waypoints
|
2018-08-10 00:34:48 -03:00
|
|
|
SIMPLE = 59, // simple mode
|
2018-09-07 01:24:06 -03:00
|
|
|
ZIGZAG = 60, // zigzag mode
|
|
|
|
ZIGZAG_SaveWP = 61, // zigzag save waypoint
|
2018-10-25 04:19:04 -03:00
|
|
|
COMPASS_LEARN = 62, // learn compass offsets
|
2018-09-07 00:07:23 -03:00
|
|
|
SAILBOAT_TACK = 63, // rover sailboat tack
|
2018-11-09 18:55:15 -04:00
|
|
|
REVERSE_THROTTLE = 64, // reverse throttle input
|
2018-09-04 23:37:33 -03:00
|
|
|
GPS_DISABLE = 65, // disable GPS for testing
|
2018-10-03 10:03:49 -03:00
|
|
|
RELAY5 = 66, // Relay5 pin on/off
|
|
|
|
RELAY6 = 67, // Relay6 pin on/off
|
2019-04-06 22:36:56 -03:00
|
|
|
STABILIZE = 68, // stabilize mode
|
|
|
|
POSHOLD = 69, // poshold mode
|
|
|
|
ALTHOLD = 70, // althold mode
|
|
|
|
FLOWHOLD = 71, // flowhold mode
|
|
|
|
CIRCLE = 72, // circle mode
|
2019-04-18 01:24:02 -03:00
|
|
|
DRIFT = 73, // drift mode
|
2019-05-27 08:48:04 -03:00
|
|
|
SAILBOAT_MOTOR_3POS = 74, // Sailboat motoring 3pos
|
2019-08-22 04:02:42 -03:00
|
|
|
SURFACE_TRACKING = 75, // Surface tracking upwards or downwards
|
2019-10-20 05:09:34 -03:00
|
|
|
STANDBY = 76, // Standby mode
|
2019-10-20 18:40:35 -03:00
|
|
|
TAKEOFF = 77, // takeoff
|
2019-11-13 19:50:45 -04:00
|
|
|
RUNCAM_CONTROL = 78, // control RunCam device
|
2019-12-21 16:07:24 -04:00
|
|
|
RUNCAM_OSD_CONTROL = 79, // control RunCam OSD
|
2019-04-18 01:24:02 -03:00
|
|
|
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
|
|
|
|
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
|
2018-04-13 23:22:14 -03:00
|
|
|
// 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
|
2019-05-27 08:48:04 -03:00
|
|
|
|
|
|
|
// inputs eventually used to replace RCMAP
|
|
|
|
MAINSAIL = 207, // mainsail input
|
2019-12-13 19:24:43 -04:00
|
|
|
FLAP = 208, // flap input
|
2018-04-13 23:22:14 -03:00
|
|
|
};
|
2019-04-03 10:23:06 -03:00
|
|
|
typedef enum AUX_FUNC aux_func_t;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2019-01-07 22:20:05 -04:00
|
|
|
// auxillary switch handling (n.b.: we store this as 2-bits!):
|
|
|
|
enum aux_switch_pos_t : uint8_t {
|
2018-04-13 23:22:14 -03:00
|
|
|
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)
|
|
|
|
};
|
|
|
|
|
2019-11-13 19:50:45 -04:00
|
|
|
bool read_3pos_switch(aux_switch_pos_t &ret) const WARN_IF_UNUSED;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
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);
|
|
|
|
|
2019-11-03 20:18:01 -04:00
|
|
|
void do_aux_function_avoid_adsb(const aux_switch_pos_t ch_flag);
|
2018-10-25 04:36:20 -03:00
|
|
|
void do_aux_function_avoid_proximity(const aux_switch_pos_t ch_flag);
|
2018-04-13 23:22:14 -03:00
|
|
|
void do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag);
|
2019-11-13 19:50:45 -04:00
|
|
|
void do_aux_function_runcam_control(const aux_switch_pos_t ch_flag);
|
2019-12-21 16:07:24 -04:00
|
|
|
void do_aux_function_runcam_osd_control(const aux_switch_pos_t ch_flag);
|
2019-08-31 12:23:08 -03:00
|
|
|
void do_aux_function_fence(const aux_switch_pos_t ch_flag);
|
2018-08-16 23:44:15 -03:00
|
|
|
void do_aux_function_clear_wp(const aux_switch_pos_t ch_flag);
|
2018-06-08 00:37:51 -03:00
|
|
|
void do_aux_function_gripper(const aux_switch_pos_t ch_flag);
|
2018-08-27 05:15:51 -03:00
|
|
|
void do_aux_function_lost_vehicle_sound(const aux_switch_pos_t ch_flag);
|
2019-06-05 20:39:14 -03:00
|
|
|
void do_aux_function_mission_reset(const aux_switch_pos_t ch_flag);
|
2018-08-02 07:48:04 -03:00
|
|
|
void do_aux_function_rc_override_enable(const aux_switch_pos_t ch_flag);
|
2018-06-08 00:37:51 -03:00
|
|
|
void do_aux_function_relay(uint8_t relay, bool val);
|
|
|
|
void do_aux_function_sprayer(const aux_switch_pos_t ch_flag);
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
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)
|
|
|
|
};
|
|
|
|
|
2019-03-29 07:27:27 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
private:
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// pwm is stored here
|
|
|
|
int16_t radio_in;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// value generated from PWM normalised to configured scale
|
|
|
|
int16_t control_in;
|
2018-12-05 04:29:49 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_Int16 radio_min;
|
|
|
|
AP_Int16 radio_trim;
|
|
|
|
AP_Int16 radio_max;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_Int8 reversed;
|
|
|
|
AP_Int16 dead_zone;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2018-09-01 21:01:11 -03:00
|
|
|
ChannelType type_in;
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t high_in;
|
2015-10-30 02:46:03 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// the input channel this corresponds to
|
|
|
|
uint8_t ch_in;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
// overrides
|
|
|
|
uint16_t override_value;
|
|
|
|
uint32_t last_override_time;
|
|
|
|
|
2018-10-12 19:56:44 -03:00
|
|
|
int16_t pwm_to_angle() const;
|
|
|
|
int16_t pwm_to_angle_dz(uint16_t dead_zone) const;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
// 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;
|
|
|
|
|
2019-06-18 12:37:19 -03:00
|
|
|
// Structure used to detect and debounce switch changes
|
|
|
|
struct {
|
|
|
|
int8_t debounce_position = -1;
|
|
|
|
int8_t current_position = -1;
|
|
|
|
uint32_t last_edge_time_ms;
|
|
|
|
} switch_state;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
void reset_mode_switch();
|
|
|
|
void read_mode_switch();
|
2019-06-18 12:37:19 -03:00
|
|
|
bool debounce_completed(int8_t position);
|
2016-10-22 07:27:40 -03:00
|
|
|
};
|
2016-05-08 05:22:32 -03:00
|
|
|
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
/*
|
|
|
|
class RC_Channels. Hold the full set of RC_Channel objects
|
|
|
|
*/
|
|
|
|
class RC_Channels {
|
|
|
|
public:
|
2017-01-08 20:47:26 -04:00
|
|
|
friend class SRV_Channels;
|
2018-04-25 23:06:19 -03:00
|
|
|
friend class RC_Channel;
|
2016-10-22 07:27:40 -03:00
|
|
|
// constructor
|
|
|
|
RC_Channels(void);
|
2016-10-11 08:00:48 -03:00
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
void init(void);
|
2016-10-22 07:27:40 -03:00
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
// get singleton instance
|
|
|
|
static RC_Channels *get_singleton() {
|
|
|
|
return _singleton;
|
2016-05-08 05:22:32 -03:00
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2018-04-26 22:00:49 -03:00
|
|
|
// compatability functions for Plane:
|
|
|
|
static uint16_t get_radio_in(const uint8_t chan) {
|
|
|
|
RC_Channel *c = _singleton->channel(chan);
|
|
|
|
if (c == nullptr) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return c->get_radio_in();
|
|
|
|
}
|
|
|
|
static RC_Channel *rc_channel(const uint8_t chan) {
|
|
|
|
return _singleton->channel(chan);
|
|
|
|
}
|
|
|
|
//end compatability functions for Plane
|
|
|
|
|
2019-12-18 23:52:33 -04:00
|
|
|
// this function is implemented in the child class in the vehicle
|
|
|
|
// code
|
2018-04-13 23:22:14 -03:00
|
|
|
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
|
2018-12-05 04:29:49 -04:00
|
|
|
// returns the number of valid channels
|
2018-04-03 23:16:36 -03:00
|
|
|
|
|
|
|
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
|
2018-12-05 04:29:49 -04:00
|
|
|
bool read_input(void); // returns true if new input has been read in
|
2018-04-03 23:16:36 -03:00
|
|
|
static void clear_overrides(void); // clears any active overrides
|
2019-01-24 08:42:46 -04:00
|
|
|
static bool receiver_bind(const int dsmMode); // puts the receiver in bind mode if present, returns true if success
|
2018-04-25 23:06:19 -03:00
|
|
|
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
|
2018-04-03 23:16:36 -03:00
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
|
|
|
|
bool duplicate_options_exist();
|
|
|
|
|
|
|
|
void init_aux_all();
|
2018-11-21 23:55:22 -04:00
|
|
|
void read_aux_all();
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
// mode switch handling
|
|
|
|
void reset_mode_switch();
|
|
|
|
virtual void read_mode_switch();
|
|
|
|
|
2018-07-31 21:10:33 -03:00
|
|
|
// has_valid_input should be pure-virtual when Plane is converted
|
|
|
|
virtual bool has_valid_input() const { return false; };
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2018-08-02 07:48:04 -03:00
|
|
|
bool gcs_overrides_enabled() const { return _gcs_overrides_enabled; }
|
|
|
|
void set_gcs_overrides_enabled(bool enable) {
|
|
|
|
_gcs_overrides_enabled = enable;
|
2018-08-02 23:23:53 -03:00
|
|
|
if (!_gcs_overrides_enabled) {
|
|
|
|
clear_overrides();
|
|
|
|
}
|
2018-08-02 07:48:04 -03:00
|
|
|
}
|
|
|
|
|
2019-03-11 18:26:59 -03:00
|
|
|
// should we ignore RC failsafe bits from receivers?
|
2019-03-29 07:27:27 -03:00
|
|
|
bool ignore_rc_failsafe(void) const {
|
2019-04-08 22:12:00 -03:00
|
|
|
return get_singleton() != nullptr && (_options & uint32_t(Option::IGNORE_FAILSAFE));
|
2019-03-29 07:27:27 -03:00
|
|
|
}
|
|
|
|
|
2020-01-01 00:33:42 -04:00
|
|
|
// should we add a pad byte to Fport data
|
|
|
|
bool fport_pad(void) const {
|
|
|
|
return get_singleton() != nullptr && (_options & uint32_t(Option::FPORT_PAD));
|
|
|
|
}
|
|
|
|
|
2019-03-29 07:27:27 -03:00
|
|
|
bool ignore_overrides() const {
|
|
|
|
return _options & uint32_t(Option::IGNORE_OVERRIDES);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool ignore_receiver() const {
|
|
|
|
return _options & uint32_t(Option::IGNORE_RECEIVER);
|
2019-03-11 18:26:59 -03:00
|
|
|
}
|
2019-03-29 07:27:27 -03:00
|
|
|
|
2019-03-29 07:45:49 -03:00
|
|
|
float override_timeout_ms() const {
|
|
|
|
return _override_timeout.get() * 1e3f;
|
|
|
|
}
|
|
|
|
|
2019-12-03 22:08:33 -04:00
|
|
|
/*
|
|
|
|
get the RC input PWM value given a channel number. Note that
|
|
|
|
channel numbers start at 1, as this API is designed for use in
|
|
|
|
LUA
|
|
|
|
*/
|
|
|
|
bool get_pwm(uint8_t channel, uint16_t &pwm) const;
|
|
|
|
|
2019-03-29 07:27:27 -03:00
|
|
|
protected:
|
|
|
|
|
|
|
|
enum class Option {
|
|
|
|
IGNORE_RECEIVER = (1 << 0), // RC receiver modules
|
|
|
|
IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides
|
|
|
|
IGNORE_FAILSAFE = (1 << 2), // ignore RC failsafe bits
|
2020-01-01 00:33:42 -04:00
|
|
|
FPORT_PAD = (1 << 3), // pad fport telem output
|
2019-03-29 07:27:27 -03:00
|
|
|
};
|
|
|
|
|
2019-03-29 07:59:29 -03:00
|
|
|
void new_override_received() {
|
|
|
|
has_new_overrides = true;
|
|
|
|
}
|
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
private:
|
2018-04-13 23:22:14 -03:00
|
|
|
static RC_Channels *_singleton;
|
2016-10-22 07:27:40 -03:00
|
|
|
// this static arrangement is to avoid static pointers in AP_Param tables
|
|
|
|
static RC_Channel *channels;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2019-03-29 07:59:29 -03:00
|
|
|
bool has_new_overrides;
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
AP_Float _override_timeout;
|
2018-07-24 22:50:01 -03:00
|
|
|
AP_Int32 _options;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2019-12-18 23:52:33 -04:00
|
|
|
// flight_mode_channel_number must be overridden in vehicle specific code
|
2018-04-13 23:22:14 -03:00
|
|
|
virtual int8_t flight_mode_channel_number() const = 0;
|
|
|
|
RC_Channel *flight_mode_channel();
|
|
|
|
|
2018-08-02 07:48:04 -03:00
|
|
|
// Allow override by default at start
|
|
|
|
bool _gcs_overrides_enabled = true;
|
2010-11-23 15:28:19 -04:00
|
|
|
};
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
RC_Channels &rc();
|