mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add RC_FS_TIMEOUT param and accessor for Copter
This commit is contained in:
parent
c7f08e422c
commit
14f729babb
|
@ -601,7 +601,10 @@ public:
|
|||
// 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
|
||||
|
||||
|
||||
// get failsafe timeout in milliseconds
|
||||
uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); }
|
||||
|
||||
protected:
|
||||
|
||||
enum class Option {
|
||||
|
@ -637,6 +640,7 @@ private:
|
|||
AP_Float _override_timeout;
|
||||
AP_Int32 _options;
|
||||
AP_Int32 _protocols;
|
||||
AP_Float _fs_timeout;
|
||||
|
||||
RC_Channel *flight_mode_channel() const;
|
||||
|
||||
|
|
|
@ -98,6 +98,14 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
|||
// @User: Advanced
|
||||
// @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS
|
||||
AP_GROUPINFO("_PROTOCOLS", 34, RC_CHANNELS_SUBCLASS, _protocols, 1),
|
||||
|
||||
|
||||
// @Param: _FS_TIMEOUT
|
||||
// @DisplayName: RC Failsafe timeout
|
||||
// @Description: RC failsafe will trigger this many seconds after loss of RC
|
||||
// @User: Standard
|
||||
// @Range: 0.5 10.0
|
||||
// @Units: s
|
||||
AP_GROUPINFO_FRAME("_FS_TIMEOUT", 35, RC_CHANNELS_SUBCLASS, _fs_timeout, 1.0, AP_PARAM_FRAME_COPTER),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue