ArduPilot开源飞控之RC_Channels

ArduPilot开源飞控之RC_Channels

  • 1. 源由
  • 2. 框架设计
    • 2.1 继承关系
      • 2.1.1 RC_Channel_Copter
      • 2.1.2 RC_Channels_Copter
      • 2.1.3 RC_Channels
      • 2.1.4 RC_Channel
    • 2.2 启动代码
    • 2.3 任务代码
  • 3. 重要例程
    • 3.1 RC_Channels
    • 3.2 init
    • 3.3 read_input
    • 3.4 update
  • 4. 总结
  • 5. 参考资料

1. 源由

Ardupilot最为主要的一个控制方式就是远程遥控控制。
RC_Channels就是遥控通道实现控制的应用类。该应用类,将RC数据从RCInput按照规定协议获取,经过数据处理、规范化。再使用特定模型应用转化方法进行应用和解释,最终得到控制飞控的应用参数,比如:当前飞行模式。

2. 框架设计

2.1 继承关系

2.1.1 RC_Channel_Copter

继承实现RC_Channel的虚函数。

class RC_Channel_Copter : public RC_Channel
{public:protected:void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;private:void do_aux_function_change_mode(const Mode::Number mode,const AuxSwitchPos ch_flag);void do_aux_function_change_air_mode(const AuxSwitchPos ch_flag);void do_aux_function_change_force_flying(const AuxSwitchPos ch_flag);// called when the mode switch changes position:void mode_switch_changed(modeswitch_pos_t new_pos) override;};

2.1.2 RC_Channels_Copter

继承实现RC_Channels的虚函数。

class RC_Channels_Copter : public RC_Channels
{
public:bool has_valid_input() const override;bool in_rc_failsafe() const override;RC_Channel *get_arming_channel(void) const override;RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];RC_Channel_Copter *channel(const uint8_t chan) override {if (chan >= NUM_RC_CHANNELS) {return nullptr;}return &obj_channels[chan];}// returns true if throttle arming checks should be runbool arming_check_throttle() const override;protected:int8_t flight_mode_channel_number() const override;};

2.1.3 RC_Channels

所有RC通道。

/*class	RC_Channels. Hold the full set of RC_Channel objects
*/
class RC_Channels {
public:friend class SRV_Channels;friend class RC_Channel;// constructorRC_Channels(void);void init(void);// get singleton instancestatic RC_Channels *get_singleton() {return _singleton;}static const struct AP_Param::GroupInfo var_info[];// 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// this function is implemented in the child class in the vehicle// codevirtual RC_Channel *channel(uint8_t chan) = 0;// helper used by scripting to convert the above function from 0 to 1 indexeing// range is checked correctly by the underlying channel functionRC_Channel *lua_rc_channel(const uint8_t chan) {return channel(chan -1);}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 channelsstatic uint8_t get_valid_channel_count(void);                      // returns the number of valid channels in the last readstatic int16_t get_receiver_rssi(void);                            // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1static int16_t get_receiver_link_quality(void);                         // returns 0-100 % of last 100 packets received at receiver are validbool read_input(void);                                             // returns true if new input has been read instatic void clear_overrides(void);                                 // clears any active overridesstatic bool receiver_bind(const int dsmMode);                      // puts the receiver in bind mode if present, returns true if successstatic void set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms = 0); // set a channels override valuestatic bool has_active_overrides(void);                            // returns true if there are overrides applied that are valid// returns a mask indicating which channels have overrides.  Bit 0// is RC channel 1.  Beware this is not a cheap call.uint16_t get_override_mask() const;class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);bool duplicate_options_exist();RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const;void convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option);void init_aux_all();void read_aux_all();// mode switch handlingvoid reset_mode_switch();virtual void read_mode_switch();virtual bool in_rc_failsafe() const { return true; };virtual bool has_valid_input() const { return false; };virtual RC_Channel *get_arming_channel(void) const { return nullptr; };bool gcs_overrides_enabled() const { return _gcs_overrides_enabled; }void set_gcs_overrides_enabled(bool enable) {_gcs_overrides_enabled = enable;if (!_gcs_overrides_enabled) {clear_overrides();}}enum class Option {IGNORE_RECEIVER         = (1U << 0), // RC receiver modulesIGNORE_OVERRIDES        = (1U << 1), // MAVLink overridesIGNORE_FAILSAFE         = (1U << 2), // ignore RC failsafe bitsFPORT_PAD               = (1U << 3), // pad fport telem outputLOG_RAW_DATA            = (1U << 4), // log rc input bytesARMING_CHECK_THROTTLE   = (1U << 5), // run an arming check for neutral throttleARMING_SKIP_CHECK_RPY   = (1U << 6), // skip the an arming checks for the roll/pitch/yaw channelsALLOW_SWITCH_REV        = (1U << 7), // honor the reversed flag on switchesCRSF_CUSTOM_TELEMETRY   = (1U << 8), // use passthrough data for crsf telemetrySUPPRESS_CRSF_MESSAGE   = (1U << 9), // suppress CRSF mode/rate message for ELRS systemsMULTI_RECEIVER_SUPPORT  = (1U << 10), // allow multiple receiversUSE_CRSF_LQ_AS_RSSI     = (1U << 11), // returns CRSF link quality as RSSI value, instead of RSSICRSF_FM_DISARM_STAR     = (1U << 12), // when disarmed, add a star at the end of the flight mode in CRSF telemetryELRS_420KBAUD           = (1U << 13), // use 420kbaud for ELRS protocol};bool option_is_enabled(Option option) const {return _options & uint32_t(option);}virtual bool arming_check_throttle() const {return option_is_enabled(Option::ARMING_CHECK_THROTTLE);}// 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 * 1e3f);return true;}if (is_zero(value)) {returned_timeout_ms = 0;return true;}// overrides will not time outreturn false;}// get mask of enabled protocolsuint32_t enabled_protocols() const;// returns true if we have had a direct detach RC receiver, does not include overridesbool has_had_rc_receiver() const { return _has_had_rc_receiver; }// returns true if we have had an override on any channelbool has_had_rc_override() const { return _has_had_override; }/*get the RC input PWM value given a channel number.  Note thatchannel numbers start at 1, as this API is designed for use inLUA*/bool get_pwm(uint8_t channel, uint16_t &pwm) const;uint32_t last_input_ms() const { return last_update_ms; };// method for other parts of the system (e.g. Button and mavlink)// to trigger auxiliary functionsbool 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);}// check if flight mode channel is assigned RC option// return true if assignedbool flight_mode_channel_conflicts_with_rc_option() const;// flight_mode_channel_number must be overridden in vehicle specific codevirtual int8_t flight_mode_channel_number() const = 0;// set and get calibrating flag, stops arming if truevoid calibrating(bool b) { gcs_is_calibrating = b; }bool calibrating() { return gcs_is_calibrating; }#if AP_SCRIPTING_ENABLED// get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos);
#endif// get failsafe timeout in millisecondsuint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); }protected:void new_override_received() {has_new_overrides = true;_has_had_override = true;}private:static RC_Channels *_singleton;// this static arrangement is to avoid static pointers in AP_Param tablesstatic RC_Channel *channels;uint32_t last_update_ms;bool has_new_overrides;bool _has_had_rc_receiver; // true if we have had a direct detach RC receiver, does not include overridesbool _has_had_override; // true if we have had an override on any channelAP_Float _override_timeout;AP_Int32  _options;AP_Int32  _protocols;AP_Float _fs_timeout;RC_Channel *flight_mode_channel() const;// Allow override by default at startbool _gcs_overrides_enabled = true;// true if GCS is performing a RC calibrationbool gcs_is_calibrating;#if AP_SCRIPTING_ENABLED// bitmask of last aux function value, 2 bits per function// value 0 means never set, otherwise level+1HAL_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
};

2.1.4 RC_Channel

单独一个RC通道。

/// @class	RC_Channel
/// @brief	Object managing one RC channel
class RC_Channel {
public:friend class SRV_Channels;friend class RC_Channels;// ConstructorRC_Channel(void);enum class ControlType {ANGLE = 0,RANGE = 1,};// setup the control preferencesvoid        set_range(uint16_t high);uint16_t    get_range() const { return high_in; }void        set_angle(uint16_t angle);bool        get_reverse(void) const;void        set_default_dead_zone(int16_t dzone);uint16_t    get_dead_zone(void) const { return dead_zone; }// get the center stick position expressed as a control_in valueint16_t     get_control_mid() const;// read input from hal.rcin - create a control_in valuebool        update(void);// calculate an angle given dead_zone and trim. This is used by the quadplane code// for hover throttleint16_t     pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim) const;// return a normalised input for a channel, in range -1 to 1,// centered around the channel trim. Ignore deadzone.float       norm_input() const;// return a normalised input for a channel, in range -1 to 1,// centered around the channel trim. Take into account the deadzonefloat       norm_input_dz() const;// return a normalised input for a channel, in range -1 to 1,// ignores trim and deadzonefloat       norm_input_ignore_trim() const;// returns true if input is within deadzone of minbool        in_min_dz() const;uint8_t     percent_input() const;static const struct AP_Param::GroupInfo var_info[];// return true if input is within deadzone of trimbool       in_trim_dz() const;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;}void       clear_override();void       set_override(const uint16_t v, const uint32_t timestamp_ms);bool       has_override() const;float    stick_mixing(const float servo_in);// get control input with zero deadzoneint16_t    get_control_in_zero_dz(void) const;int16_t    get_radio_min() const {return radio_min.get();}int16_t    get_radio_max() const {return radio_max.get();}int16_t    get_radio_trim() const { return radio_trim.get();}void       set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);}// set and save trim if changedvoid       set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}// check if any of the trim/min/max param are configured, this would indicate that the user has done a calibration at somepointbool       configured() { return radio_min.configured() || radio_max.configured() || radio_trim.configured(); }ControlType get_type(void) const { return type_in; }AP_Int16    option; // e.g. activate EPM gripper / enable fence// auxiliary switch supportvoid init_aux();bool read_aux();// Aux Switch enumerationenum class AUX_FUNC {DO_NOTHING =           0, // aux switch disabledFLIP =                 2, // flipSIMPLE_MODE =          3, // change to simple modeRTL =                  4, // change to RTL flight modeSAVE_TRIM =            5, // save current position as levelSAVE_WP =              7, // save mission waypoint or RTL if in auto modeCAMERA_TRIGGER =       9, // trigger camera servo or relayRANGEFINDER =         10, // allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the groundFENCE =               11, // allow enabling or disabling fence in flightRESETTOARMEDYAW =     12, // UNUSEDSUPERSIMPLE_MODE =    13, // change to simple mode in middle, super simple at topACRO_TRAINER =        14, // low = disabled, middle = leveled, high = leveled and limitedSPRAYER =             15, // enable/disable the crop sprayerAUTO =                16, // change to auto flight modeAUTOTUNE =            17, // auto tuneLAND =                18, // change to LAND flight modeGRIPPER =             19, // Operate cargo grippers low=off, middle=neutral, high=onPARACHUTE_ENABLE  =   21, // Parachute enable/disablePARACHUTE_RELEASE =   22, // Parachute releasePARACHUTE_3POS =      23, // Parachute disable, enable, release with 3 position switchMISSION_RESET =       24, // Reset auto mission to start from first commandATTCON_FEEDFWD =      25, // enable/disable the roll and pitch rate feed forwardATTCON_ACCEL_LIM =    26, // enable/disable the roll, pitch and yaw accel limitingRETRACT_MOUNT1 =      27, // Retract Mount1RELAY =               28, // Relay pin on/off (only supports first relay)LANDING_GEAR =        29, // Landing gear controllerLOST_VEHICLE_SOUND =  30, // Play lost vehicle soundMOTOR_ESTOP =         31, // Emergency Stop SwitchMOTOR_INTERLOCK =     32, // Motor On/Off switchBRAKE =               33, // Brake flight modeRELAY2 =              34, // Relay2 pin on/offRELAY3 =              35, // Relay3 pin on/offRELAY4 =              36, // Relay4 pin on/offTHROW =               37, // change to THROW flight modeAVOID_ADSB =          38, // enable AP_Avoidance libraryPRECISION_LOITER =    39, // enable precision loiterAVOID_PROXIMITY =     40, // enable object avoidance using proximity sensors (ie. horizontal lidar)ARMDISARM_UNUSED =    41, // UNUSEDSMART_RTL =           42, // change to SmartRTL flight modeINVERTED  =           43, // enable inverted flightWINCH_ENABLE =        44, // winch enable/disableWINCH_CONTROL =       45, // winch controlRC_OVERRIDE_ENABLE =  46, // enable RC OverrideUSER_FUNC1 =          47, // user function #1USER_FUNC2 =          48, // user function #2USER_FUNC3 =          49, // user function #3LEARN_CRUISE =        50, // learn cruise throttle (Rover)MANUAL       =        51, // manual modeACRO         =        52, // acro modeSTEERING     =        53, // steering modeHOLD         =        54, // hold modeGUIDED       =        55, // guided modeLOITER       =        56, // loiter modeFOLLOW       =        57, // follow modeCLEAR_WP     =        58, // clear waypointsSIMPLE       =        59, // simple modeZIGZAG       =        60, // zigzag modeZIGZAG_SaveWP =       61, // zigzag save waypointCOMPASS_LEARN =       62, // learn compass offsetsSAILBOAT_TACK =       63, // rover sailboat tackREVERSE_THROTTLE =    64, // reverse throttle inputGPS_DISABLE  =        65, // disable GPS for testingRELAY5 =              66, // Relay5 pin on/offRELAY6 =              67, // Relay6 pin on/offSTABILIZE =           68, // stabilize modePOSHOLD   =           69, // poshold modeALTHOLD   =           70, // althold modeFLOWHOLD  =           71, // flowhold modeCIRCLE    =           72, // circle modeDRIFT     =           73, // drift modeSAILBOAT_MOTOR_3POS = 74, // Sailboat motoring 3posSURFACE_TRACKING =    75, // Surface tracking upwards or downwardsSTANDBY  =            76, // Standby modeTAKEOFF   =           77, // takeoffRUNCAM_CONTROL =      78, // control RunCam deviceRUNCAM_OSD_CONTROL =  79, // control RunCam OSDVISODOM_ALIGN =       80, // align visual odometry camera's attitude to AHRSDISARM =              81, // disarm vehicleQ_ASSIST =            82, // disable, enable and force Q assistZIGZAG_Auto =         83, // zigzag auto switchAIRMODE =             84, // enable / disable airmode for copterGENERATOR   =         85, // generator controlTER_DISABLE =         86, // disable terrain following in CRUISE/FBWB modesCROW_SELECT =         87, // select CROW mode for diff spoilers;high disables,mid forces progressiveSOARING =             88, // three-position switch to set soaring modeLANDING_FLARE =       89, // force flare, throttle forced idle, pitch to LAND_PITCH_CD, tilts upEKF_POS_SOURCE =      90, // change EKF position source between primary, secondary and tertiary sourcesARSPD_CALIBRATE=      91, // calibrate airspeed ratio FBWA =                92, // Fly-By-Wire-ARELOCATE_MISSION =    93, // used in separate branch MISSION_RELATIVEVTX_POWER =           94, // VTX power levelFBWA_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.MODE_SWITCH_RESET =   96, // trigger re-reading of mode switchWIND_VANE_DIR_OFSSET= 97, // flag for windvane direction offset input, used with windvane type 2TRAINING            = 98, // mode trainingAUTO_RTL =            99, // AUTO RTL via DO_LAND_START// entries from 100-150  are expected to be developer// options used for testingKILL_IMU1 =          100, // disable first IMU (for IMU failure testing)KILL_IMU2 =          101, // disable second IMU (for IMU failure testing)CAM_MODE_TOGGLE =    102, // Momentary switch to cycle camera modesEKF_LANE_SWITCH =    103, // trigger lane switch attemptEKF_YAW_RESET =      104, // trigger yaw reset attemptGPS_DISABLE_YAW =    105, // disable GPS yaw for testingDISABLE_AIRSPEED_USE = 106, // equivalent to AIRSPEED_USE 0FW_AUTOTUNE =          107, // fixed wing auto tuneQRTL =               108, // QRTL modeCUSTOM_CONTROLLER =  109,  // use Custom ControllerKILL_IMU3 =          110, // disable third IMU (for IMU failure testing)LOWEHEISER_STARTER = 111,  // allows for manually running starter// 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// options 150-199 continue user rc switch optionsCRUISE =             150,  // CRUISE modeTURTLE =             151,  // Turtle mode - flip over after crashSIMPLE_HEADING_RESET = 152, // reset simple mode reference heading to currentARMDISARM =          153, // arm or disarm vehicleARMDISARM_AIRMODE =  154, // arm or disarm vehicle enabling airmodeTRIM_TO_CURRENT_SERVO_RC = 155, // trim to current servo and RCTORQEEDO_CLEAR_ERR = 156, // clear torqeedo errorEMERGENCY_LANDING_EN = 157, //Force long FS action to FBWA for landing out of rangeOPTFLOW_CAL =        158, // optical flow calibrationFORCEFLYING =        159, // enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_maxWEATHER_VANE_ENABLE = 160, // enable/disable weathervaningTURBINE_START =      161, // initialize turbine start sequenceFFT_NOTCH_TUNE =     162, // FFT notch tuning functionMOUNT_LOCK =         163, // Mount yaw lock vs followLOG_PAUSE =          164, // Pauses logging if under logging rate controlARM_EMERGENCY_STOP = 165, // ARM on high, MOTOR_ESTOP on lowCAMERA_REC_VIDEO =   166, // start recording on high, stop recording on lowCAMERA_ZOOM =        167, // camera zoom high = zoom in, middle = hold, low = zoom outCAMERA_MANUAL_FOCUS = 168,// camera manual focus.  high = long shot, middle = stop focus, low = close shotCAMERA_AUTO_FOCUS =  169, // camera auto focusQSTABILIZE =         170, // QuadPlane QStabilize modeMAG_CAL =            171, // Calibrate compasses (disarmed only)BATTERY_MPPT_ENABLE = 172,// Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs.PLANE_AUTO_LANDING_ABORT = 173, // Abort Glide-slope or VTOL landing during payload place or do_land type mission itemsCAMERA_IMAGE_TRACKING = 174, // camera image trackingCAMERA_LENS =        175, // camera lens selectionVFWD_THR_OVERRIDE =  176, // force enabled VTOL forward throttle method// inputs from 200 will eventually used to replace RCMAPROLL =               201, // roll inputPITCH =              202, // pitch inputTHROTTLE =           203, // throttle pilot inputYAW =                204, // yaw pilot inputMAINSAIL =           207, // mainsail inputFLAP =               208, // flap inputFWD_THR =            209, // VTOL manual forward throttleAIRBRAKE =           210, // manual airbrake controlWALKING_HEIGHT =     211, // walking robot height inputMOUNT1_ROLL =        212, // mount1 roll inputMOUNT1_PITCH =       213, // mount1 pitch inputMOUNT1_YAW =         214, // mount1 yaw inputMOUNT2_ROLL =        215, // mount2 roll inputMOUNT2_PITCH =       216, // mount3 pitch inputMOUNT2_YAW =         217, // mount4 yaw inputLOWEHEISER_THROTTLE= 218,  // allows for throttle on slider// inputs 248-249 are reserved for the Skybrush fork at// https://github.com/skybrush-io/ardupilot// inputs for the use of onboard lua scriptingSCRIPTING_1 =        300,SCRIPTING_2 =        301,SCRIPTING_3 =        302,SCRIPTING_4 =        303,SCRIPTING_5 =        304,SCRIPTING_6 =        305,SCRIPTING_7 =        306,SCRIPTING_8 =        307,// this must be higher than any aux function aboveAUX_FUNCTION_MAX =   308,};typedef enum AUX_FUNC aux_func_t;// auxiliary switch handling (n.b.: we store this as 2-bits!):enum class AuxSwitchPos : uint8_t {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)};enum class AuxFuncTriggerSource : uint8_t {INIT,RC,BUTTON,MAVLINK,MISSION,SCRIPTING,};AuxSwitchPos get_aux_switch_pos() const;// wrapper function around do_aux_function which allows us to logbool run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source);#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLEDconst char *string_for_aux_function(AUX_FUNC function) const;const char *string_for_aux_pos(AuxSwitchPos pos) const;
#endif// pwm value under which we consider that Radio value is invalidstatic const uint16_t RC_MIN_LIMIT_PWM = 800;// pwm value above which we consider that Radio value is invalidstatic const uint16_t RC_MAX_LIMIT_PWM = 2200;// pwm value above which we condider that Radio min value is invalidstatic const uint16_t RC_CALIB_MIN_LIMIT_PWM = 1300;// pwm value under which we condider that Radio max value is invalidstatic const uint16_t RC_CALIB_MAX_LIMIT_PWM = 1700;// 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;// pwm value above which the option will be invoked:static const uint16_t AUX_PWM_TRIGGER_HIGH = 1700;// pwm value below which the option will be disabled:static const uint16_t AUX_PWM_TRIGGER_LOW = 1300;protected:virtual void init_aux_function(aux_func_t ch_option, AuxSwitchPos);// virtual function to be overridden my subclassesvirtual bool do_aux_function(aux_func_t ch_option, AuxSwitchPos);void do_aux_function_armdisarm(const AuxSwitchPos ch_flag);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);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);bool do_aux_function_camera_image_tracking(const AuxSwitchPos ch_flag);bool do_aux_function_camera_lens(const AuxSwitchPos ch_flag);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);void do_aux_function_mission_reset(const AuxSwitchPos ch_flag);void do_aux_function_rc_override_enable(const AuxSwitchPos ch_flag);void do_aux_function_relay(uint8_t relay, bool val);void do_aux_function_sprayer(const AuxSwitchPos ch_flag);void do_aux_function_generator(const AuxSwitchPos ch_flag);void do_aux_function_fft_notch_tune(const AuxSwitchPos 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 hereint16_t     radio_in;// value generated from PWM normalised to configured scaleint16_t    control_in;AP_Int16    radio_min;AP_Int16    radio_trim;AP_Int16    radio_max;AP_Int8     reversed;AP_Int16    dead_zone;ControlType type_in;int16_t     high_in;// the input channel this corresponds touint8_t     ch_in;// overridesuint16_t override_value;uint32_t last_override_time;int16_t pwm_to_angle() const;int16_t pwm_to_angle_dz(uint16_t dead_zone) const;int16_t pwm_to_range() const;int16_t pwm_to_range_dz(uint16_t dead_zone) const;bool read_3pos_switch(AuxSwitchPos &ret) const WARN_IF_UNUSED;bool read_6pos_switch(int8_t& position) WARN_IF_UNUSED;// Structure used to detect and debounce switch changesstruct {int8_t debounce_position = -1;int8_t current_position = -1;uint32_t last_edge_time_ms;} switch_state;void reset_mode_switch();void read_mode_switch();bool debounce_completed(int8_t position);#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED// Structure to lookup switch change announcementsstruct LookupTable{AUX_FUNC option;const char *announcement;};static const LookupTable lookuptable[];
#endif
};

2.2 启动代码

Copter::init_ardupilot└──> RC_Channels::init

2.3 任务代码

SCHED_TASK(rc_loop,              250,    130,  3),└──> Copter::rc_loop└──> Copter::read_radio└──> RC_Channels::read_input

3. 重要例程

3.1 RC_Channels

RC通道唯一实例对象初始化。

RC_Channels::RC_Channels││  // set defaults from the parameter table├──> AP_Param::setup_object_defaults(this, var_info)││  // only one instance├──> <_singleton != nullptr>│   └──> AP_HAL::panic("RC_Channels must be singleton")└──> _singleton = this

3.2 init

初始化所有RC通道。

RC_Channels::init││   // setup ch_in on channels├──> <for (uint8_t i=0 i<NUM_RC_CHANNELS i++)>│   └──> channel(i)->ch_in = i└──> init_aux_all()
RC_Channels::init_aux_all├──> <for (uint8_t i=0 i<NUM_RC_CHANNELS i++)>│   ├──> RC_Channel *c = channel(i)│   ├──> <c == nullptr>│   │   └──> continue│   └──> c->init_aux()└──> reset_mode_switch()

3.3 read_input

// update all the input channels
RC_Channels::read_input││   //check rc new input├──> <hal.rcin->new_input()) {│   └──> _has_had_rc_receiver = true├──> < else if (!has_new_overrides) >│   └──> return false├──> has_new_overrides = false│├──> last_update_ms = AP_HAL::millis()││   //update all rc channels├──> bool success = false├──> <for (uint8_t i=0 i<NUM_RC_CHANNELS i++)>│   └──> success |= channel(i)->update()└──> return success

3.4 update

RC遥控数据,详见:ArduPilot开源代码之RCInput

// read input from hal.rcin or overrides
RC_Channel::update││   //update rc channel in├──> <has_override() && !rc().option_is_enabled(RC_Channels::Option::IGNORE_OVERRIDES)>│   └──> radio_in = override_value├──> < else if (rc().has_had_rc_receiver() && !rc().option_is_enabled(RC_Channels::Option::IGNORE_RECEIVER))>│   └──> radio_in = hal.rcin->read(ch_in)├──> < else >│   └──> return false││   //calculate deadzone├──> <type_in == ControlType::RANGE>│   └──> control_in = pwm_to_range()├──> < else >│   └──> control_in = pwm_to_angle() // // ControlType::ANGLE└──> return true

4. 总结

从整个代码设计逻辑上可以分析出以下几点:

  1. RC_Channels_Copter完善Copter模型RC_Channels类的应用实现;
  2. RC_Channel_Copter完善Copter模型RC_Channel类的应用实现;
  3. RC原始遥控通道数据来源于RC_Channel类的update方法;
  4. RC遥控协议的解析主要在RCInput完成;

RC数据流方向:RCInput ==》 RC_Channel + RC_Channel_Copter ==》 RC_Channels + RC_Channels_Copter

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mzph.cn/news/113669.shtml

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

电机矢量控制算法和例程

电机矢量控制算法是一种高级的电机控制方法&#xff0c;它通过将电机转子空间矢量转换到旋转坐标系中&#xff0c;并在该坐标系中进行控制来实现对电机的精确控制。下面是对电机矢量控制算法的详细解释&#xff1a; 坐标系变换&#xff1a;电机矢量控制首先将电机转子空间矢量变…

0基础学习PyFlink——模拟Hadoop流程

学习大数据还是绕不开始祖级别的技术hadoop。我们不用了解其太多&#xff0c;只要理解其大体流程&#xff0c;然后用python代码模拟主要流程来熟悉其思想。 还是以单词统计为例&#xff0c;如果使用hadoop流程实现&#xff0c;则如下图。 为什么要搞这么复杂呢&#xff1f; 顾…

操作系统【OS】进程的控制结构PCB

进程的控制结构 PCB 程序段 数据段 PCB PCB 是进程存在的唯一标识一个进程的存在&#xff0c;必然会有一个 PCB&#xff0c;如果进程消失了&#xff0c;那么 PCB 也会随之消失PCB常驻内存 PCB包含什么信息? 进程描述信息 进程标识符PID&#xff1a;标识各个进程&#…

git常见错误信息及解决方法

Git 是一个很好的项目管理系统&#xff0c;唯一的缺点就是是英文的&#xff0c;而我又英语太差&#xff0c;再加上时不时会出现一些奇怪的报错&#xff0c;让人头大。所以这里就简单记录一些我遇到的报错和我是怎么解决的。 20230226 warning: in the working copy of package…

详解API基础知识

目录 什么是API: API 的设计原则包括&#xff1a; API 的开发流程包括以下几个步骤&#xff1a; API 的使用场景包括&#xff1a; API 的优势包括&#xff1a; 然而&#xff0c;API 也存在一些挑战和问题&#xff0c;例如&#xff1a; 什么是API: API&#xff08;应用程…

JS监听按键,禁止F12,禁止右键,禁止保存网页

禁止右键&#xff1a; document.oncontextmenu new Function("event.returnValuefalse;") //禁用右键禁止按键&#xff1a; // 监听按键 document.onkeydown function () {// f12if (window.event && window.event.keyCode 123) {alert("F12被禁用…

Linux内核8. Linux内核的经典调试方式

1 内核调试以及工具总结 内核总是那么捉摸不透, 内核也会犯错, 但是调试却不能像用户空间程序那样, 为此内核开发者为我们提供了一系列的工具和系统来支持内核的调试. 内核的调试, 其本质是内核空间与用户空间的数据交换, 内核开发者们提供了多样的形式来完成这一功能. 2 用户…

从输入URL到展示出页面

目录 了解URL 1. 输入URL 2. 域名解析 3. 建立连接 4. 服务器处理请求&#xff1a; 5. 返回响应&#xff1a; 6. 浏览器解析HTML&#xff1a; 7. 加载资源&#xff1a; 8. 渲染页面&#xff1a; 9. 执行JavaScript&#xff1a; 10. 页面展示&#xff1a; 从输入URL到…

为什么实际开发中不推荐使用外键?

为什么实际开发中不推荐使用外键&#xff1f; 只有一个场景不能使用外键&#xff0c;就是分库分表&#xff0c;其它描述都不是真正原因。 性能问题&#xff1f; 数据库的瓶颈在IO&#xff0c;不使用外键代码里做数据完整性检查&#xff0c;磁盘IO省不了&#xff0c;网络IO占用…

AWS SAP-C02教程10-其它服务

接下来介绍的内容是一些SAP-C02考试会涉及到的,但是目前无法很好将其归类,暂且放在其它服务中 目录 1 AWS WorkSpaces2 AWS APP Stream 2.02.1 WorkSpaces vs APP Stream 2.03 AWS Device Farm4 AWS AppSync5 AWS Outposts6 AWS WaveLength7 AWS Local Zones8 AWS Cloud Map…

docker 部署redis报错内存分配过度

之间部署redis集群的时候报错 2023 10:20:29.131 # WARNING Memory overcommit must be enabled! Without it, a background save or replication may fail under low memory condition. Being disabled, it can also cause failures without low memory condition, see https:…

一台服务器,一个新世界

我如何看待服务器 当我拥有一台服务器&#xff0c;我看到的不仅仅是一块硬件&#xff0c;而是一扇打开未来的大门&#xff0c;一个我可以将自己的愿景和创意投射到其中的平台。这台服务器是我的工具&#xff0c;我的画布&#xff0c;我将在其中铸造我的数字梦想。 第一步我要…

Cesium Vue(四)— 物体(Entity)的添加与配置

1. 添加标签和广告牌 // 添加文字标签和广告牌var label viewer.entities.add({position: Cesium.Cartesian3.fromDegrees(113.3191, 23.109, 750),label: {text: "广州塔",font: "24px sans-serif",fillColor: Cesium.Color.WHITE,outlineColor: Cesium.…

C/S架构学习之使用select实现TCP小型并发服务器

select实现TCP小型并发服务器的流程&#xff1a;一、创建套接字&#xff08;socket函数&#xff09;&#xff1a;通信域选择IPV4网络协议、套接字类型选择流式&#xff1b; int sockfd socket(AF_INET,SOCK_STREAM,0); //通信域选择IPV4、套接字类型选择流式二、填充服务器的网…

Centos 无法连接 WIFI

环境 硬件&#xff1a;ASUS X550VC, x86_64系统&#xff1a;CentOS 7.9 现象 系统安装后无法上网&#xff0c;终端命令提示符为shadow3dlocalhost&#xff0c;我的疑问是这里不是应该显示我的主机名吗&#xff0c;为什么是localhost呢&#xff1f;但是有些时候&#xff0c;又…

蛋白质折叠

文章目录 4. GNNs for Protein foldingChemical Structures as GraphsProtein Structure PredictionMethods for Protein Structure PredictionOld method: fragment assemblyNew StrategyCo-evolution Analysis Towards An End-to-End Workflow AlphaFold2 architecture补充&a…

MySQL:BETWEEN AND操作符的边界

文档原文&#xff1a; expr BETWEEN min AND maxIf expr is greater than or equal to min and expr is less than or equal to max, BETWEEN returns 1, otherwise it returns 0. This is equivalent to the expression (min < expr AND expr < max) if all the argume…

水管安装过滤器笔记

文章目录 方案准备工具剪管钳热熔器软管接头及单向阀扳手 操作过程花洒 搬家后&#xff0c;水质不行&#xff0c;洗脸掉皮&#xff0c;洗头以前不掉头皮屑的&#xff0c;居然也掉头皮屑。有必要简单过滤下了。 水质情况&#xff0c;并不是脏脏的的那种水&#xff0c;看上去还比…

QString字符串判断是否包含中文

目的 QString判断是否包含中文。 实现方式 可以通过以下两种方式实现&#xff1a; 逐一取QString的字符&#xff0c;判断其Unicode码位是否处于中文的范围之内。具体代码实现如下&#xff1a; QString str; int nCount str.count(); bool containsChinese false; …

檀香香料经营商城小程序的作用是什么

檀香香料有安神、驱蚊、清香等作用&#xff0c;办公室或家庭打坐等场景&#xff0c;都有较高的使用频率&#xff0c;不同香料也有不同效果&#xff0c;高品质香料檀香也一直受不少消费者欢迎。 线下流量匮乏&#xff0c;又难以实现全消费路径完善&#xff0c;线上是商家增长必…