RCOutput_AeroIO.cpp 7.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  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. #include "RCOutput_AeroIO.h"
  18. #include <utility>
  19. #include <AP_HAL/AP_HAL.h>
  20. #include <AP_HAL/utility/sparse-endian.h>
  21. #include <AP_Math/AP_Math.h>
  22. using namespace Linux;
  23. // Device name in @SPIDeviceDriver#_device
  24. #define DEVICE_NAME "aeroio"
  25. // Number of channels
  26. #define PWM_CHAN_COUNT 16
  27. // Set all channels
  28. #define ALL_CHAN_MASK ((1 << PWM_CHAN_COUNT) - 1)
  29. // Default PWM frequency
  30. #define DEFAULT_FREQ 400
  31. // Default PWM duty cycle
  32. #define DEFAULT_DUTY 0
  33. // Set or Clear MSb of BYTE
  34. #define WADDRESS(x) ((x) | 0x8000)
  35. #define RADDRESS(x) ((x) & 0x7FFF)
  36. // Variables to perform ongoing tests
  37. #define READ_PREFIX 0x80
  38. #define WRITE_PREFIX 0x40
  39. /**
  40. * The data_array uses 3 elements to perform the data transaction.
  41. * The first element is a data byte that provides to FPGA's hardware
  42. * the transaction type that will be realized inside the SPI module.
  43. * Where:
  44. *
  45. * ╔═════════╦═════════╦══════════╦══════════╦══════════╦══════════╦══════════╦═══════════╗
  46. * ║ MSB ║ ║ ║ ║ ║ ║ ║ LSB ║
  47. * ╠═════════╬═════════╬══════════╬══════════╬══════════╬══════════╬══════════╬═══════════╣
  48. * ║ wr_addr ║ rd_addr ║ reserved ║ reserved ║ reserved ║ reserved ║ reserved ║ reserved ║
  49. * ╚═════════╩═════════╩══════════╩══════════╩══════════╩══════════╩══════════╩═══════════╝
  50. *
  51. * ╔═══════════╦═════════╦═════════╗
  52. * ║ Register ║ wr_addr ║ rd_addr ║
  53. * ╠═══════════╬═════════╬═════════╣
  54. * ║ write ║ 0 ║ X ║
  55. * ╠═══════════╬═════════╬═════════╣
  56. * ║ read ║ X ║ 0 ║
  57. * ╠═══════════╬═════════╬═════════╣
  58. * ║ status ║ 1 ║ 1 ║
  59. * ╚═══════════╩═════════╩═════════╝
  60. *
  61. * So, to perform a write transaction in the SPI module it's necessary to send. E.g:
  62. * 0b 01xx xxxx
  63. * And to a read transaction..
  64. * 0b 10xx xxxx
  65. *
  66. * The PWM frequency is always even and the duty cycle percentage odd. E.g:
  67. * pwm_01: Address 0x0000 frequency
  68. * : Address 0x0001 duty cycle
  69. * pwm_02: Address 0x0002 frequency
  70. * .
  71. * .
  72. * .
  73. *
  74. * Eg of allowed values:
  75. * // PWM channel in 100Hz
  76. * uint16_t freq = 100;
  77. *
  78. * // duty cycle in (1823/65535) that's 2.78% of 100Hz:
  79. * // the signal will hold high until 278 usec
  80. * uint16_t duty = 1823;
  81. */
  82. static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  83. RCOutput_AeroIO::RCOutput_AeroIO()
  84. : _freq_buffer(new uint16_t[PWM_CHAN_COUNT])
  85. , _duty_buffer(new uint16_t[PWM_CHAN_COUNT])
  86. {
  87. }
  88. RCOutput_AeroIO::~RCOutput_AeroIO()
  89. {
  90. delete[] _freq_buffer;
  91. delete[] _duty_buffer;
  92. }
  93. void RCOutput_AeroIO::init()
  94. {
  95. _spi = std::move(hal.spi->get_device(DEVICE_NAME));
  96. if (!_spi) {
  97. AP_HAL::panic("Could not initialize AeroIO");
  98. }
  99. // Reset all channels to default value
  100. cork();
  101. set_freq(ALL_CHAN_MASK, DEFAULT_FREQ);
  102. for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
  103. write(i, DEFAULT_DUTY);
  104. }
  105. push();
  106. }
  107. void RCOutput_AeroIO::set_freq(uint32_t chmask, uint16_t freq_hz)
  108. {
  109. _pending_freq_write_mask |= chmask;
  110. for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
  111. if ((chmask >> i) & 0x01) {
  112. _freq_buffer[i] = freq_hz;
  113. }
  114. }
  115. if (!_corking) {
  116. _corking = true;
  117. push();
  118. }
  119. }
  120. uint16_t RCOutput_AeroIO::get_freq(uint8_t ch)
  121. {
  122. if (ch >= PWM_CHAN_COUNT) {
  123. return 0;
  124. }
  125. return _freq_buffer[ch];
  126. }
  127. void RCOutput_AeroIO::enable_ch(uint8_t ch)
  128. {
  129. if (ch >= PWM_CHAN_COUNT) {
  130. return;
  131. }
  132. _pending_duty_write_mask |= (1U << ch);
  133. _corking = true;
  134. push();
  135. }
  136. void RCOutput_AeroIO::disable_ch(uint8_t ch)
  137. {
  138. if (ch >= PWM_CHAN_COUNT) {
  139. return;
  140. }
  141. _duty_buffer[ch] = 0;
  142. _pending_duty_write_mask |= (1U << ch);
  143. _corking = true;
  144. push();
  145. }
  146. void RCOutput_AeroIO::write(uint8_t ch, uint16_t period_us)
  147. {
  148. _pending_duty_write_mask |= (1U << ch);
  149. _duty_buffer[ch] = period_us;
  150. if (!_corking) {
  151. _corking = true;
  152. push();
  153. }
  154. }
  155. void RCOutput_AeroIO::cork()
  156. {
  157. _corking = true;
  158. }
  159. void RCOutput_AeroIO::push()
  160. {
  161. if (!_corking) {
  162. return;
  163. }
  164. _corking = false;
  165. for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
  166. if ((_pending_freq_write_mask >> i) & 0x01) {
  167. _hw_write(2 * i + 1, _freq_buffer[i]);
  168. }
  169. }
  170. for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
  171. if ((_pending_duty_write_mask >> i) & 0x01) {
  172. _hw_write(2 * i, _usec_to_hw(_freq_buffer[i], _duty_buffer[i]));
  173. }
  174. }
  175. _pending_freq_write_mask = _pending_duty_write_mask = 0;
  176. }
  177. uint16_t RCOutput_AeroIO::read(uint8_t ch)
  178. {
  179. if (ch >= PWM_CHAN_COUNT) {
  180. return 0;
  181. }
  182. #ifndef AEROIO_DEBUG
  183. return _duty_buffer[ch];
  184. #else
  185. return _hw_to_usec(_freq_buffer[ch], _hw_read(2 * ch));
  186. #endif
  187. }
  188. void RCOutput_AeroIO::read(uint16_t *period_us, uint8_t len)
  189. {
  190. for (uint8_t i = 0; i < len; i++) {
  191. period_us[i] = read(i);
  192. }
  193. }
  194. bool RCOutput_AeroIO::_hw_write(uint16_t address, uint16_t data)
  195. {
  196. struct PACKED {
  197. uint8_t prefix;
  198. be16_t addr;
  199. be16_t val;
  200. } tx;
  201. address = WADDRESS(address);
  202. tx.prefix = WRITE_PREFIX;
  203. tx.addr = htobe16(address);
  204. tx.val = htobe16(data);
  205. return _spi->transfer((uint8_t *)&tx, sizeof(tx), nullptr, 0);
  206. }
  207. uint16_t RCOutput_AeroIO::_hw_read(uint16_t address)
  208. {
  209. struct PACKED {
  210. uint8_t prefix;
  211. be16_t addr;
  212. } tx;
  213. struct PACKED {
  214. uint8_t ignored[2];
  215. be16_t val;
  216. } rx;
  217. address = RADDRESS(address);
  218. // Write in the SPI buffer the address value
  219. tx.prefix = WRITE_PREFIX;
  220. tx.addr = htobe16(address);
  221. if (!_spi->transfer((uint8_t *)&tx, sizeof(tx), nullptr, 0)) {
  222. return 0;
  223. }
  224. /*
  225. * Read the SPI buffer, sending only the prefix as tx
  226. * The hardware will fill in 32 bits after the request
  227. */
  228. tx.prefix = READ_PREFIX;
  229. if (!_spi->transfer((uint8_t *)&tx, 1, (uint8_t *)&rx, sizeof(rx))) {
  230. return 0;
  231. }
  232. return be16toh(rx.val);
  233. }
  234. uint16_t RCOutput_AeroIO::_usec_to_hw(uint16_t freq, uint16_t usec)
  235. {
  236. float f = freq;
  237. float u = usec;
  238. return 0xFFFF * u * f / AP_USEC_PER_SEC;
  239. }
  240. uint16_t RCOutput_AeroIO::_hw_to_usec(uint16_t freq, uint16_t hw_val)
  241. {
  242. float p = hw_val;
  243. float f = freq;
  244. return p * AP_USEC_PER_SEC / (0xFFFF * f);
  245. }