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
2023-03-19 03:30:17 -03:00
# include "RC_Channel_config.h"
# if AP_RC_CHANNEL_ENABLED
2015-08-11 03:28:46 -03:00
# include <AP_Common/AP_Common.h>
# include <AP_Param/AP_Param.h>
2020-01-23 01:07:48 -04:00
# include <AP_Math/AP_Math.h>
2022-10-09 21:34:19 -03:00
# include <AP_Common/Bitmask.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
2022-02-25 02:01:06 -04:00
enum class ControlType {
ANGLE = 0 ,
RANGE = 1 ,
2018-09-01 21:01:11 -03:00
} ;
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 ) ;
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
2020-02-21 23:22:30 -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
2020-02-21 23:22:30 -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
2020-02-21 23:22:13 -04:00
// return a normalised input for a channel, in range -1 to 1,
// ignores trim and deadzone
float norm_input_ignore_trim ( ) const ;
2021-11-20 20:03:18 -04:00
// returns true if input is within deadzone of min
2022-03-05 01:10:22 -04:00
bool in_min_dz ( ) const ;
2021-11-20 20:03:18 -04:00
2018-10-12 19:56:44 -03:00
uint8_t percent_input ( ) 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 ( ) ;
2020-02-07 21:27:16 -04:00
void set_override ( const uint16_t v , const uint32_t timestamp_ms ) ;
2018-04-25 23:06:19 -03:00
bool has_override ( ) const ;
2021-09-18 14:55:21 -03:00
float stick_mixing ( const float servo_in ) ;
2019-05-01 17:43:27 -03:00
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 ( ) ; }
int16_t get_radio_max ( ) const { return radio_max . get ( ) ; }
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 ( ) ; }
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
2022-05-11 19:04:37 -03:00
// check if any of the trim/min/max param are configured, this would indicate that the user has done a calibration at somepoint
bool configured ( ) { return radio_min . configured ( ) | | radio_max . configured ( ) | | radio_trim . configured ( ) ; }
2021-09-15 19:31:32 -03:00
2022-02-25 02:01:06 -04:00
ControlType get_type ( void ) const { return type_in ; }
2018-09-01 21:01:11 -03:00
2018-04-13 23:22:14 -03:00
AP_Int16 option ; // e.g. activate EPM gripper / enable fence
2020-02-21 23:22:30 -04:00
// auxiliary switch support
2018-04-13 23:22:14 -03:00
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
2022-09-12 22:37:34 -03:00
RETRACT_MOUNT1 = 27 , // Retract Mount1
2018-04-13 23:22:14 -03:00
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)
2021-09-13 21:37:44 -03:00
ARMDISARM_UNUSED = 41 , // UNUSED
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
2021-08-20 02:40:44 -03:00
VISODOM_ALIGN = 80 , // align visual odometry camera's attitude to AHRS
2020-04-30 11:54:22 -03:00
DISARM = 81 , // disarm vehicle
2020-01-02 15:04:42 -04:00
Q_ASSIST = 82 , // disable, enable and force Q assist
2020-04-03 01:46:29 -03:00
ZIGZAG_Auto = 83 , // zigzag auto switch
2020-05-24 08:25:42 -03:00
AIRMODE = 84 , // enable / disable airmode for copter
2020-06-30 14:54:00 -03:00
GENERATOR = 85 , // generator control
TER_DISABLE = 86 , // disable terrain following in CRUISE/FBWB modes
2020-07-15 16:22:50 -03:00
CROW_SELECT = 87 , // select CROW mode for diff spoilers;high disables,mid forces progressive
2020-07-13 05:45:57 -03:00
SOARING = 88 , // three-position switch to set soaring mode
2020-10-02 21:52:56 -03:00
LANDING_FLARE = 89 , // force flare, throttle forced idle, pitch to LAND_PITCH_CD, tilts up
2020-06-17 03:35:46 -03:00
EKF_POS_SOURCE = 90 , // change EKF position source between primary, secondary and tertiary sources
2020-11-24 10:13:10 -04:00
ARSPD_CALIBRATE = 91 , // calibrate airspeed ratio
2020-12-14 23:22:14 -04:00
FBWA = 92 , // Fly-By-Wire-A
2021-01-22 13:34:40 -04:00
RELOCATE_MISSION = 93 , // used in separate branch MISSION_RELATIVE
2021-02-07 09:20:55 -04:00
VTX_POWER = 94 , // VTX power level
2021-03-12 17:57:07 -04:00
FBWA_TAILDRAGGER = 95 , // enables FBWA taildragger takeoff mode. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA.
2021-03-16 11:07:47 -03:00
MODE_SWITCH_RESET = 96 , // trigger re-reading of mode switch
2021-04-10 19:19:54 -03:00
WIND_VANE_DIR_OFSSET = 97 , // flag for windvane direction offset input, used with windvane type 2
2021-07-17 21:20:40 -03:00
TRAINING = 98 , // mode training
2021-07-24 20:21:30 -03:00
AUTO_RTL = 99 , // AUTO RTL via DO_LAND_START
2020-07-15 16:22:50 -03:00
2021-08-09 22:54:59 -03:00
// entries from 100-150 are expected to be developer
2020-06-18 20:55:38 -03:00
// options used for testing
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)
2020-02-09 15:30:22 -04:00
CAM_MODE_TOGGLE = 102 , // Momentary switch to cycle camera modes
2020-03-02 01:56:48 -04:00
EKF_LANE_SWITCH = 103 , // trigger lane switch attempt
EKF_YAW_RESET = 104 , // trigger yaw reset attempt
2020-05-20 23:23:26 -03:00
GPS_DISABLE_YAW = 105 , // disable GPS yaw for testing
2021-06-17 03:03:35 -03:00
DISABLE_AIRSPEED_USE = 106 , // equivalent to AIRSPEED_USE 0
2021-11-08 23:30:43 -04:00
FW_AUTOTUNE = 107 , // fixed wing auto tune
2021-11-21 16:43:44 -04:00
QRTL = 108 , // QRTL mode
2023-08-25 21:46:05 -03:00
CUSTOM_CONTROLLER = 109 , // use Custom Controller
2022-10-15 07:00:39 -03:00
KILL_IMU3 = 110 , // disable third IMU (for IMU failure testing)
2022-02-08 23:14:42 -04:00
LOWEHEISER_STARTER = 111 , // allows for manually running starter
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
2021-08-09 22:54:59 -03:00
// options 150-199 continue user rc switch options
2022-01-31 11:34:06 -04:00
CRUISE = 150 , // CRUISE mode
2021-08-12 04:33:52 -03:00
TURTLE = 151 , // Turtle mode - flip over after crash
2022-06-01 01:01:22 -03:00
SIMPLE_HEADING_RESET = 152 , // reset simple mode reference heading to current
2021-09-13 21:37:44 -03:00
ARMDISARM = 153 , // arm or disarm vehicle
ARMDISARM_AIRMODE = 154 , // arm or disarm vehicle enabling airmode
2021-09-21 18:17:26 -03:00
TRIM_TO_CURRENT_SERVO_RC = 155 , // trim to current servo and RC
2021-09-21 08:33:36 -03:00
TORQEEDO_CLEAR_ERR = 156 , // clear torqeedo error
2021-10-24 02:20:43 -03:00
EMERGENCY_LANDING_EN = 157 , //Force long FS action to FBWA for landing out of range
2020-10-08 22:32:03 -03:00
OPTFLOW_CAL = 158 , // optical flow calibration
2022-01-31 11:34:06 -04:00
FORCEFLYING = 159 , // enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max
2022-01-23 18:07:53 -04:00
WEATHER_VANE_ENABLE = 160 , // enable/disable weathervaning
2022-03-06 08:51:31 -04:00
TURBINE_START = 161 , // initialize turbine start sequence
FFT_NOTCH_TUNE = 162 , // FFT notch tuning function
2022-06-01 01:39:42 -03:00
MOUNT_LOCK = 163 , // Mount yaw lock vs follow
2022-07-26 20:41:04 -03:00
LOG_PAUSE = 164 , // Pauses logging if under logging rate control
2022-08-19 12:06:24 -03:00
ARM_EMERGENCY_STOP = 165 , // ARM on high, MOTOR_ESTOP on low
2022-09-27 01:53:48 -03:00
CAMERA_REC_VIDEO = 166 , // start recording on high, stop recording on low
CAMERA_ZOOM = 167 , // camera zoom high = zoom in, middle = hold, low = zoom out
CAMERA_MANUAL_FOCUS = 168 , // camera manual focus. high = long shot, middle = stop focus, low = close shot
CAMERA_AUTO_FOCUS = 169 , // camera auto focus
2022-12-01 05:15:07 -04:00
QSTABILIZE = 170 , // QuadPlane QStabilize mode
2023-02-14 09:56:52 -04:00
MAG_CAL = 171 , // Calibrate compasses (disarmed only)
2023-02-17 15:58:31 -04:00
BATTERY_MPPT_ENABLE = 172 , // Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs.
2023-03-13 22:29:52 -03:00
PLANE_AUTO_LANDING_ABORT = 173 , // Abort Glide-slope or VTOL landing during payload place or do_land type mission items
2023-04-28 21:58:00 -03:00
CAMERA_IMAGE_TRACKING = 174 , // camera image tracking
2023-07-14 08:20:04 -03:00
CAMERA_LENS = 175 , // camera lens selection
2023-09-08 00:14:18 -03:00
VFWD_THR_OVERRIDE = 176 , // force enabled VTOL forward throttle method
2023-03-07 17:17:52 -04:00
2021-08-09 22:54:59 -03:00
2020-06-18 20:55:38 -03:00
// inputs from 200 will eventually used to replace RCMAP
2020-07-10 21:20:42 -03:00
ROLL = 201 , // roll input
PITCH = 202 , // pitch input
2021-03-02 02:30:47 -04:00
THROTTLE = 203 , // throttle pilot input
YAW = 204 , // yaw pilot input
2019-05-27 08:48:04 -03:00
MAINSAIL = 207 , // mainsail input
2019-12-13 19:24:43 -04:00
FLAP = 208 , // flap input
2020-06-09 19:02:53 -03:00
FWD_THR = 209 , // VTOL manual forward throttle
2018-11-12 11:41:22 -04:00
AIRBRAKE = 210 , // manual airbrake control
2021-03-02 02:30:47 -04:00
WALKING_HEIGHT = 211 , // walking robot height input
2022-08-30 04:29:24 -03:00
MOUNT1_ROLL = 212 , // mount1 roll input
MOUNT1_PITCH = 213 , // mount1 pitch input
MOUNT1_YAW = 214 , // mount1 yaw input
MOUNT2_ROLL = 215 , // mount2 roll input
MOUNT2_PITCH = 216 , // mount3 pitch input
MOUNT2_YAW = 217 , // mount4 yaw input
2022-02-08 23:14:42 -04:00
LOWEHEISER_THROTTLE = 218 , // allows for throttle on slider
2020-07-07 20:15:05 -03:00
2022-08-02 06:16:03 -03:00
// inputs 248-249 are reserved for the Skybrush fork at
// https://github.com/skybrush-io/ardupilot
2020-07-07 20:15:05 -03:00
// inputs for the use of onboard lua scripting
SCRIPTING_1 = 300 ,
SCRIPTING_2 = 301 ,
SCRIPTING_3 = 302 ,
SCRIPTING_4 = 303 ,
SCRIPTING_5 = 304 ,
SCRIPTING_6 = 305 ,
SCRIPTING_7 = 306 ,
SCRIPTING_8 = 307 ,
2022-10-09 21:34:19 -03:00
// this must be higher than any aux function above
AUX_FUNCTION_MAX = 308 ,
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
2022-01-21 05:12:00 -04:00
// auxiliary switch handling (n.b.: we store this as 2-bits!):
2020-06-02 23:21:50 -03:00
enum class AuxSwitchPos : 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)
} ;
2021-04-28 06:13:53 -03:00
enum class AuxFuncTriggerSource : uint8_t {
INIT ,
RC ,
BUTTON ,
MAVLINK ,
MISSION ,
2021-05-02 09:15:47 -03:00
SCRIPTING ,
2021-04-28 06:13:53 -03:00
} ;
2020-06-02 23:21:50 -03:00
AuxSwitchPos get_aux_switch_pos ( ) const ;
2019-11-13 19:50:45 -04:00
2021-04-28 06:13:53 -03:00
// wrapper function around do_aux_function which allows us to log
bool run_aux_function ( aux_func_t ch_option , AuxSwitchPos pos , AuxFuncTriggerSource source ) ;
2020-10-01 02:17:02 -03:00
2022-10-06 07:44:29 -03:00
# if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
2020-10-15 00:57:53 -03:00
const char * string_for_aux_function ( AUX_FUNC function ) const ;
2022-10-13 13:41:28 -03:00
const char * string_for_aux_pos ( AuxSwitchPos pos ) const ;
2020-10-15 00:57:53 -03:00
# endif
2021-05-11 09:32:53 -03:00
// pwm value under which we consider that Radio value is invalid
2022-02-14 20:35:51 -04:00
static const uint16_t RC_MIN_LIMIT_PWM = 800 ;
2021-05-11 09:32:53 -03:00
// pwm value above which we consider that Radio value is invalid
static const uint16_t RC_MAX_LIMIT_PWM = 2200 ;
2020-04-02 11:33:23 -03:00
// pwm value above which we condider that Radio min value is invalid
static const uint16_t RC_CALIB_MIN_LIMIT_PWM = 1300 ;
// pwm value under which we condider that Radio max value is invalid
static const uint16_t RC_CALIB_MAX_LIMIT_PWM = 1700 ;
2021-02-03 13:21:28 -04:00
// pwm value above which the switch/button will be invoked:
static const uint16_t AUX_SWITCH_PWM_TRIGGER_HIGH = 1800 ;
// pwm value below which the switch/button will be disabled:
static const uint16_t AUX_SWITCH_PWM_TRIGGER_LOW = 1200 ;
2020-10-15 00:57:53 -03:00
2020-10-01 02:04:16 -03:00
// pwm value above which the option will be invoked:
2021-02-03 13:21:39 -04:00
static const uint16_t AUX_PWM_TRIGGER_HIGH = 1700 ;
2020-10-01 02:04:16 -03:00
// pwm value below which the option will be disabled:
2021-02-03 13:21:39 -04:00
static const uint16_t AUX_PWM_TRIGGER_LOW = 1300 ;
2020-10-01 02:04:16 -03:00
2019-11-13 19:50:45 -04:00
protected :
2020-06-02 23:21:50 -03:00
virtual void init_aux_function ( aux_func_t ch_option , AuxSwitchPos ) ;
2021-04-28 06:13:53 -03:00
// virtual function to be overridden my subclasses
virtual bool do_aux_function ( aux_func_t ch_option , AuxSwitchPos ) ;
2021-09-13 21:38:14 -03:00
void do_aux_function_armdisarm ( const AuxSwitchPos ch_flag ) ;
2020-06-02 23:21:50 -03:00
void do_aux_function_avoid_adsb ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_avoid_proximity ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_camera_trigger ( const AuxSwitchPos ch_flag ) ;
2022-09-27 01:53:48 -03:00
bool do_aux_function_record_video ( const AuxSwitchPos ch_flag ) ;
bool do_aux_function_camera_zoom ( const AuxSwitchPos ch_flag ) ;
bool do_aux_function_camera_manual_focus ( const AuxSwitchPos ch_flag ) ;
bool do_aux_function_camera_auto_focus ( const AuxSwitchPos ch_flag ) ;
2023-04-28 21:58:00 -03:00
bool do_aux_function_camera_image_tracking ( const AuxSwitchPos ch_flag ) ;
2023-07-14 08:20:04 -03:00
bool do_aux_function_camera_lens ( const AuxSwitchPos ch_flag ) ;
2020-06-02 23:21:50 -03:00
void do_aux_function_runcam_control ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_runcam_osd_control ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_fence ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_clear_wp ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_gripper ( const AuxSwitchPos ch_flag ) ;
void do_aux_function_lost_vehicle_sound ( const AuxSwitchPos ch_flag ) ;
2021-08-05 10:46:05 -03:00
void do_aux_function_mission_reset ( const AuxSwitchPos ch_flag ) ;
2020-06-02 23:21:50 -03:00
void do_aux_function_rc_override_enable ( const AuxSwitchPos ch_flag ) ;
2018-06-08 00:37:51 -03:00
void do_aux_function_relay ( uint8_t relay , bool val ) ;
2020-06-02 23:21:50 -03:00
void do_aux_function_sprayer ( const AuxSwitchPos ch_flag ) ;
2019-11-26 23:09:52 -04:00
void do_aux_function_generator ( const AuxSwitchPos ch_flag ) ;
2022-03-06 08:51:31 -04:00
void do_aux_function_fft_notch_tune ( const AuxSwitchPos 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
2022-02-25 02:01:06 -04:00
ControlType 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
2022-02-25 02:42:42 -04:00
int16_t pwm_to_range ( ) const ;
int16_t pwm_to_range_dz ( uint16_t dead_zone ) const ;
2022-02-25 02:55:48 -04:00
bool read_3pos_switch ( AuxSwitchPos & ret ) const WARN_IF_UNUSED ;
bool read_6pos_switch ( int8_t & position ) WARN_IF_UNUSED ;
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 ) ;
2020-06-02 22:42:20 -03:00
2022-10-06 07:44:29 -03:00
# if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
2020-06-02 22:42:20 -03:00
// Structure to lookup switch change announcements
struct LookupTable {
AUX_FUNC option ;
const char * announcement ;
} ;
static const LookupTable lookuptable [ ] ;
# endif
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 ;
2021-08-04 16:47:25 -03:00
// helper used by scripting to convert the above function from 0 to 1 indexeing
// range is checked correctly by the underlying channel function
RC_Channel * lua_rc_channel ( const uint8_t chan ) {
return channel ( chan - 1 ) ;
}
2018-04-13 23:22:14 -03:00
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
2021-07-13 13:45:08 -03:00
static int16_t get_receiver_link_quality ( void ) ; // returns 0-100 % of last 100 packets received at receiver are valid
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
2021-05-15 00:45:43 -03:00
// returns a mask indicating which channels have overrides. Bit 0
// is RC channel 1. Beware this is not a cheap call.
2022-01-03 09:37:23 -04:00
uint16_t get_override_mask ( ) const ;
2021-05-15 00:45:43 -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 ( ) ;
2020-06-02 23:21:50 -03:00
RC_Channel : : AuxSwitchPos get_channel_pos ( const uint8_t rcmapchan ) const ;
2021-09-13 21:38:43 -03:00
void convert_options ( const RC_Channel : : aux_func_t old_option , const RC_Channel : : aux_func_t new_option ) ;
2018-04-13 23:22:14 -03:00
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 ( ) ;
2023-06-22 20:10:42 -03:00
virtual bool in_rc_failsafe ( ) const { return true ; } ;
2018-07-31 21:10:33 -03:00
virtual bool has_valid_input ( ) const { return false ; } ;
2018-04-13 23:22:14 -03:00
2020-03-30 23:08:24 -03:00
virtual RC_Channel * get_arming_channel ( void ) const { return nullptr ; } ;
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
}
2023-06-11 02:13:42 -03:00
enum class Option {
IGNORE_RECEIVER = ( 1U < < 0 ) , // RC receiver modules
IGNORE_OVERRIDES = ( 1U < < 1 ) , // MAVLink overrides
IGNORE_FAILSAFE = ( 1U < < 2 ) , // ignore RC failsafe bits
FPORT_PAD = ( 1U < < 3 ) , // pad fport telem output
LOG_RAW_DATA = ( 1U < < 4 ) , // log rc input bytes
ARMING_CHECK_THROTTLE = ( 1U < < 5 ) , // run an arming check for neutral throttle
ARMING_SKIP_CHECK_RPY = ( 1U < < 6 ) , // skip the an arming checks for the roll/pitch/yaw channels
ALLOW_SWITCH_REV = ( 1U < < 7 ) , // honor the reversed flag on switches
CRSF_CUSTOM_TELEMETRY = ( 1U < < 8 ) , // use passthrough data for crsf telemetry
SUPPRESS_CRSF_MESSAGE = ( 1U < < 9 ) , // suppress CRSF mode/rate message for ELRS systems
MULTI_RECEIVER_SUPPORT = ( 1U < < 10 ) , // allow multiple receivers
USE_CRSF_LQ_AS_RSSI = ( 1U < < 11 ) , // returns CRSF link quality as RSSI value, instead of RSSI
CRSF_FM_DISARM_STAR = ( 1U < < 12 ) , // when disarmed, add a star at the end of the flight mode in CRSF telemetry
ELRS_420KBAUD = ( 1U < < 13 ) , // use 420kbaud for ELRS protocol
} ;
2019-03-29 07:27:27 -03:00
2023-06-11 02:13:42 -03:00
bool option_is_enabled ( Option option ) const {
return _options & uint32_t ( option ) ;
2019-03-11 18:26:59 -03:00
}
2019-03-29 07:27:27 -03:00
2021-09-17 20:51:40 -03:00
virtual bool arming_check_throttle ( ) const {
2023-06-11 02:13:42 -03:00
return option_is_enabled ( Option : : ARMING_CHECK_THROTTLE ) ;
2022-12-11 18:23:07 -04:00
}
2020-01-23 01:07:48 -04:00
// returns true if overrides should time out. If true is returned
// then returned_timeout_ms will contain the timeout in
// milliseconds, with 0 meaning overrides are disabled.
bool get_override_timeout_ms ( uint32_t & returned_timeout_ms ) const {
const float value = _override_timeout . get ( ) ;
if ( is_positive ( value ) ) {
returned_timeout_ms = uint32_t ( value * 1e3 f ) ;
return true ;
}
if ( is_zero ( value ) ) {
returned_timeout_ms = 0 ;
return true ;
}
// overrides will not time out
return false ;
2019-03-29 07:45:49 -03:00
}
2020-05-18 19:37:55 -03:00
2020-08-12 23:28:28 -03:00
// get mask of enabled protocols
uint32_t enabled_protocols ( ) const ;
2023-04-05 01:43:50 -03:00
// returns true if we have had a direct detach RC receiver, does not include overrides
2020-05-18 19:37:55 -03:00
bool has_had_rc_receiver ( ) const { return _has_had_rc_receiver ; }
2022-10-08 21:33:12 -03:00
// returns true if we have had an override on any channel
bool has_had_rc_override ( ) const { return _has_had_override ; }
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 ;
2020-03-30 23:08:24 -03:00
uint32_t last_input_ms ( ) const { return last_update_ms ; } ;
2021-04-28 06:13:53 -03:00
// method for other parts of the system (e.g. Button and mavlink)
2022-01-21 05:12:00 -04:00
// to trigger auxiliary functions
2021-04-28 06:13:53 -03:00
bool run_aux_function ( RC_Channel : : AUX_FUNC ch_option , RC_Channel : : AuxSwitchPos pos , RC_Channel : : AuxFuncTriggerSource source ) {
return rc_channel ( 0 ) - > run_aux_function ( ch_option , pos , source ) ;
2021-02-17 21:04:20 -04:00
}
2021-06-16 22:13:54 -03:00
// check if flight mode channel is assigned RC option
// return true if assigned
2021-06-22 01:13:51 -03:00
bool flight_mode_channel_conflicts_with_rc_option ( ) const ;
2021-06-16 22:13:54 -03:00
// flight_mode_channel_number must be overridden in vehicle specific code
virtual int8_t flight_mode_channel_number ( ) const = 0 ;
2021-08-30 12:54:15 -03:00
// set and get calibrating flag, stops arming if true
void calibrating ( bool b ) { gcs_is_calibrating = b ; }
bool calibrating ( ) { return gcs_is_calibrating ; }
2022-10-09 21:34:19 -03:00
# if AP_SCRIPTING_ENABLED
// get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2
bool get_aux_cached ( RC_Channel : : aux_func_t aux_fn , uint8_t & pos ) ;
# endif
2022-11-14 22:25:34 -04:00
// get failsafe timeout in milliseconds
uint32_t get_fs_timeout_ms ( ) const { return MAX ( _fs_timeout * 1000 , 100 ) ; }
2019-03-29 07:27:27 -03:00
protected :
2019-03-29 07:59:29 -03:00
void new_override_received ( ) {
has_new_overrides = true ;
2022-10-08 21:33:12 -03:00
_has_had_override = true ;
2019-03-29 07:59:29 -03:00
}
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
2020-03-30 23:08:24 -03:00
uint32_t last_update_ms ;
2019-03-29 07:59:29 -03:00
bool has_new_overrides ;
2023-04-05 01:43:50 -03:00
bool _has_had_rc_receiver ; // true if we have had a direct detach RC receiver, does not include overrides
2022-10-08 21:33:12 -03:00
bool _has_had_override ; // true if we have had an override on any channel
2019-03-29 07:59:29 -03:00
2018-04-25 23:06:19 -03:00
AP_Float _override_timeout ;
2018-07-24 22:50:01 -03:00
AP_Int32 _options ;
2020-08-12 23:28:28 -03:00
AP_Int32 _protocols ;
2022-11-14 22:25:34 -04:00
AP_Float _fs_timeout ;
2018-04-13 23:22:14 -03:00
2021-06-22 01:13:51 -03:00
RC_Channel * flight_mode_channel ( ) const ;
2018-04-13 23:22:14 -03:00
2018-08-02 07:48:04 -03:00
// Allow override by default at start
bool _gcs_overrides_enabled = true ;
2021-08-30 12:54:15 -03:00
// true if GCS is performing a RC calibration
bool gcs_is_calibrating ;
2022-10-09 21:34:19 -03:00
# if AP_SCRIPTING_ENABLED
// bitmask of last aux function value, 2 bits per function
// value 0 means never set, otherwise level+1
HAL_Semaphore aux_cache_sem ;
Bitmask < unsigned ( RC_Channel : : AUX_FUNC : : AUX_FUNCTION_MAX ) * 2 > aux_cached ;
void set_aux_cached ( RC_Channel : : aux_func_t aux_fn , RC_Channel : : AuxSwitchPos pos ) ;
# endif
2010-11-23 15:28:19 -04:00
} ;
2018-04-13 23:22:14 -03:00
RC_Channels & rc ( ) ;
2023-03-19 03:30:17 -03:00
# endif // AP_RC_CHANNEL_ENABLED