RCOutput_AeroIO.h 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155
  1. /*
  2. * Copyright (C) 2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #pragma once
  18. #include "AP_HAL_Linux.h"
  19. namespace Linux {
  20. class RCOutput_AeroIO : public AP_HAL::RCOutput {
  21. public:
  22. RCOutput_AeroIO();
  23. ~RCOutput_AeroIO();
  24. void init() override;
  25. /**
  26. * Enable channel
  27. */
  28. void enable_ch(uint8_t ch) override;
  29. /**
  30. * Disable channel (0 of duty cycle)
  31. */
  32. void disable_ch(uint8_t ch) override;
  33. /**
  34. * Set all channels in the same frequency
  35. *
  36. * @chmask Bitmask
  37. * @freq_hz Frequency
  38. */
  39. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  40. /**
  41. * Get frequency of channel
  42. *
  43. * @ch channel
  44. *
  45. * Return: frequency of this channel
  46. */
  47. uint16_t get_freq(uint8_t ch) override;
  48. /**
  49. * Set period in µs
  50. *
  51. * @ch channel
  52. * @period_us time in µs
  53. */
  54. void write(uint8_t ch, uint16_t period_us) override;
  55. void cork() override;
  56. void push() override;
  57. /**
  58. * Get period of the duty cycle in µs
  59. */
  60. uint16_t read(uint8_t ch) override;
  61. /**
  62. * Set @period_us with the values in µs of each channel
  63. *
  64. * @period_us vector that will be filled with duty cycle periods of
  65. * each channel
  66. * @len size of period_us vector
  67. */
  68. void read(uint16_t *period_us, uint8_t len) override;
  69. private:
  70. /**
  71. * Convert from µs to hw units, 16bits percentage of
  72. * the frequency, where 0xFFFF is 1/Freq seconds in high
  73. *
  74. * @freq Frequency
  75. * @usec Time in µseconds
  76. *
  77. * Return: conversion from µs in a specific frequency to 16bits
  78. */
  79. static uint16_t _usec_to_hw(uint16_t freq, uint16_t usec);
  80. /**
  81. * Convert from hw units, 16bits percentage of the frequency, to
  82. * time in µs
  83. *
  84. * @freq Frequency
  85. * @hw_val 16b percentage
  86. */
  87. static uint16_t _hw_to_usec(uint16_t freq, uint16_t hw_val);
  88. /**
  89. * Low-level spi write
  90. *
  91. * @address register address
  92. * @data value to be written
  93. *
  94. * Return: true on success, false otherwise
  95. */
  96. bool _hw_write(uint16_t address, uint16_t data);
  97. /**
  98. * Low-level spi read
  99. *
  100. * @address register address
  101. *
  102. * Return: value read from @address
  103. */
  104. uint16_t _hw_read(uint16_t address);
  105. AP_HAL::OwnPtr<AP_HAL::Device> _spi;
  106. /**
  107. * Frequency buffer of last written values
  108. */
  109. uint16_t *_freq_buffer;
  110. /**
  111. * Duty cycle buffer of last written values
  112. */
  113. uint16_t *_duty_buffer;
  114. /**
  115. * Save information about the channel that will be write in the
  116. * next @RCOutput_AeroIO#push call.
  117. *
  118. * 0b...101
  119. * ││└── 1st channel (Pending operation)
  120. * │└─── 2nd Channel (No pending operation)
  121. * └──── 3rd Channel (Pending operation)
  122. */
  123. uint32_t _pending_duty_write_mask = 0;
  124. uint32_t _pending_freq_write_mask = 0;
  125. /**
  126. * If <B>true</B> the push must be called to perform the writing,
  127. * otherwise will be not necessary.
  128. */
  129. bool _corking = false;
  130. };
  131. }