AP_RCMapper.h 1.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. #pragma once
  2. #include <inttypes.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_Param/AP_Param.h>
  5. class RCMapper {
  6. public:
  7. RCMapper();
  8. /* Do not allow copies */
  9. RCMapper(const RCMapper &other) = delete;
  10. RCMapper &operator=(const RCMapper&) = delete;
  11. /// roll - return input channel number for roll / aileron input
  12. uint8_t roll() const { return _ch_roll; }
  13. /// pitch - return input channel number for pitch / elevator input
  14. uint8_t pitch() const { return _ch_pitch; }
  15. /// throttle - return input channel number for throttle input
  16. uint8_t throttle() const { return _ch_throttle; }
  17. /// yaw - return input channel number for yaw / rudder input
  18. uint8_t yaw() const { return _ch_yaw; }
  19. /// forward - return input channel number for forward input
  20. uint8_t forward() const { return _ch_forward; }
  21. /// lateral - return input channel number for lateral input
  22. uint8_t lateral() const { return _ch_lateral; }
  23. static const struct AP_Param::GroupInfo var_info[];
  24. private:
  25. // channel mappings
  26. AP_Int8 _ch_roll;
  27. AP_Int8 _ch_pitch;
  28. AP_Int8 _ch_yaw;
  29. AP_Int8 _ch_throttle;
  30. AP_Int8 _ch_forward;
  31. AP_Int8 _ch_lateral;
  32. };