RCOutput.cpp 1.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3. #include "RCOutput.h"
  4. #define ENABLE_DEBUG 0
  5. #if ENABLE_DEBUG
  6. # include <stdio.h>
  7. # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while (0)
  8. #else
  9. # define Debug(fmt, args ...)
  10. #endif
  11. using namespace HALSITL;
  12. void RCOutput::init() {}
  13. void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
  14. {
  15. Debug("set_freq(0x%04x, %u)\n", static_cast<uint32_t>(chmask), static_cast<uint32_t>(freq_hz));
  16. _freq_hz = freq_hz;
  17. }
  18. uint16_t RCOutput::get_freq(uint8_t ch)
  19. {
  20. return _freq_hz;
  21. }
  22. void RCOutput::enable_ch(uint8_t ch)
  23. {
  24. if (!(_enable_mask & (1U << ch))) {
  25. Debug("enable_ch(%u)\n", ch);
  26. }
  27. _enable_mask |= 1U << ch;
  28. }
  29. void RCOutput::disable_ch(uint8_t ch)
  30. {
  31. if (_enable_mask & (1U << ch)) {
  32. Debug("disable_ch(%u)\n", ch);
  33. }
  34. _enable_mask &= ~1U << ch;
  35. }
  36. void RCOutput::write(uint8_t ch, uint16_t period_us)
  37. {
  38. _sitlState->output_ready = true;
  39. if (ch < SITL_NUM_CHANNELS && (_enable_mask & (1U<<ch))) {
  40. if (_corked) {
  41. _pending[ch] = period_us;
  42. } else {
  43. _sitlState->pwm_output[ch] = period_us;
  44. }
  45. }
  46. }
  47. uint16_t RCOutput::read(uint8_t ch)
  48. {
  49. if (ch < SITL_NUM_CHANNELS) {
  50. return _sitlState->pwm_output[ch];
  51. }
  52. return 0;
  53. }
  54. void RCOutput::read(uint16_t* period_us, uint8_t len)
  55. {
  56. memcpy(period_us, _sitlState->pwm_output, len * sizeof(uint16_t));
  57. }
  58. void RCOutput::cork(void)
  59. {
  60. if (!_corked) {
  61. memcpy(_pending, _sitlState->pwm_output, SITL_NUM_CHANNELS * sizeof(uint16_t));
  62. _corked = true;
  63. }
  64. }
  65. void RCOutput::push(void)
  66. {
  67. if (_corked) {
  68. memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
  69. _corked = false;
  70. }
  71. }
  72. #endif