mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 01:54:18 -03:00
AP_HAL: bind receivers directly via AP_RCProtocol library
... rather than via RC_Channels and the HAL and *then* to the AP_RCProtocol library...
This commit is contained in:
parent
1ac1510cec
commit
772599290b
@ -36,7 +36,7 @@ public:
|
||||
virtual int16_t get_rssi(void) { return -1; }
|
||||
virtual int16_t get_rx_link_quality(void) { return -1; }
|
||||
/* Return string describing method RC input protocol */
|
||||
virtual const char *protocol() const = 0;
|
||||
virtual const char *protocol() const { return nullptr; }
|
||||
|
||||
/**
|
||||
* Overrides: these are really grody and don't belong here but we need
|
||||
@ -47,9 +47,6 @@ public:
|
||||
* v > 0 -> set v as override.
|
||||
*/
|
||||
|
||||
/* execute receiver bind */
|
||||
virtual bool rc_bind(int dsmMode) { return false; }
|
||||
|
||||
/* enable or disable pulse input for RC input. This is used to
|
||||
reduce load when we are decoding R/C via a UART */
|
||||
virtual void pulse_input_enable(bool enable) { }
|
||||
|
Loading…
Reference in New Issue
Block a user