RCInput.h 1.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152
  1. #pragma once
  2. #include "AP_HAL_Namespace.h"
  3. #define RC_INPUT_MIN_PULSEWIDTH 900
  4. #define RC_INPUT_MAX_PULSEWIDTH 2100
  5. class AP_HAL::RCInput {
  6. public:
  7. /**
  8. * Call init from the platform hal instance init, so that both the type of
  9. * the RCInput implementation and init argument (e.g. ISRRegistry) are
  10. * known to the programmer. (It's too difficult to describe this dependency
  11. * in the C++ type system.)
  12. */
  13. virtual void init() = 0;
  14. virtual void teardown() {};
  15. /**
  16. * Return true if there has been new input since the last call to new_input()
  17. */
  18. virtual bool new_input(void) = 0;
  19. /**
  20. * Return the number of valid channels in the last read
  21. */
  22. virtual uint8_t num_channels() = 0;
  23. /* Read a single channel at a time */
  24. virtual uint16_t read(uint8_t ch) = 0;
  25. /* Read an array of channels, return the valid count */
  26. virtual uint8_t read(uint16_t* periods, uint8_t len) = 0;
  27. /* get receiver based RSSI if available. -1 for unknown, 0 for no link, 255 for maximum link */
  28. virtual int16_t get_rssi(void) { return -1; }
  29. /* Return string describing method RC input protocol */
  30. virtual const char *protocol() const = 0;
  31. /**
  32. * Overrides: these are really grody and don't belong here but we need
  33. * them at the moment to make the port work.
  34. * case v of:
  35. * v == -1 -> no change to this channel
  36. * v == 0 -> do not override this channel
  37. * v > 0 -> set v as override.
  38. */
  39. /* execute receiver bind */
  40. virtual bool rc_bind(int dsmMode) { return false; }
  41. };