RCOutput_PCA9685.cpp 6.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251
  1. #include "RCOutput_PCA9685.h"
  2. #include <cmath>
  3. #include <dirent.h>
  4. #include <fcntl.h>
  5. #include <stdint.h>
  6. #include <stdio.h>
  7. #include <stdlib.h>
  8. #include <sys/stat.h>
  9. #include <sys/types.h>
  10. #include <unistd.h>
  11. #include <utility>
  12. #include <AP_HAL/AP_HAL.h>
  13. #include "GPIO.h"
  14. #define PCA9685_RA_MODE1 0x00
  15. #define PCA9685_RA_MODE2 0x01
  16. #define PCA9685_RA_LED0_ON_L 0x06
  17. #define PCA9685_RA_LED0_ON_H 0x07
  18. #define PCA9685_RA_LED0_OFF_L 0x08
  19. #define PCA9685_RA_LED0_OFF_H 0x09
  20. #define PCA9685_RA_ALL_LED_ON_L 0xFA
  21. #define PCA9685_RA_ALL_LED_ON_H 0xFB
  22. #define PCA9685_RA_ALL_LED_OFF_L 0xFC
  23. #define PCA9685_RA_ALL_LED_OFF_H 0xFD
  24. #define PCA9685_RA_PRE_SCALE 0xFE
  25. #define PCA9685_MODE1_RESTART_BIT (1 << 7)
  26. #define PCA9685_MODE1_EXTCLK_BIT (1 << 6)
  27. #define PCA9685_MODE1_AI_BIT (1 << 5)
  28. #define PCA9685_MODE1_SLEEP_BIT (1 << 4)
  29. #define PCA9685_MODE1_SUB1_BIT (1 << 3)
  30. #define PCA9685_MODE1_SUB2_BIT (1 << 2)
  31. #define PCA9685_MODE1_SUB3_BIT (1 << 1)
  32. #define PCA9685_MODE1_ALLCALL_BIT (1 << 0)
  33. #define PCA9685_ALL_LED_OFF_H_SHUT (1 << 4)
  34. #define PCA9685_MODE2_INVRT_BIT (1 << 4)
  35. #define PCA9685_MODE2_OCH_BIT (1 << 3)
  36. #define PCA9685_MODE2_OUTDRV_BIT (1 << 2)
  37. #define PCA9685_MODE2_OUTNE1_BIT (1 << 1)
  38. #define PCA9685_MODE2_OUTNE0_BIT (1 << 0)
  39. /*
  40. * Drift for internal oscillator
  41. * see: https://github.com/ArduPilot/ardupilot/commit/50459bdca0b5a1adf95
  42. * and https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library/issues/11
  43. */
  44. #define PCA9685_INTERNAL_CLOCK (1.04f * 25000000.f)
  45. #define PCA9685_EXTERNAL_CLOCK 24576000.f
  46. using namespace Linux;
  47. #define PWM_CHAN_COUNT 16
  48. static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  49. RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  50. bool external_clock,
  51. uint8_t channel_offset,
  52. int16_t oe_pin_number) :
  53. _dev(std::move(dev)),
  54. _enable_pin(nullptr),
  55. _frequency(50),
  56. _pulses_buffer(new uint16_t[PWM_CHAN_COUNT - channel_offset]),
  57. _external_clock(external_clock),
  58. _channel_offset(channel_offset),
  59. _oe_pin_number(oe_pin_number)
  60. {
  61. if (_external_clock)
  62. _osc_clock = PCA9685_EXTERNAL_CLOCK;
  63. else
  64. _osc_clock = PCA9685_INTERNAL_CLOCK;
  65. }
  66. RCOutput_PCA9685::~RCOutput_PCA9685()
  67. {
  68. delete [] _pulses_buffer;
  69. }
  70. void RCOutput_PCA9685::init()
  71. {
  72. reset_all_channels();
  73. /* Set the initial frequency */
  74. set_freq(0, 50);
  75. /* Enable PCA9685 PWM */
  76. if (_oe_pin_number != -1) {
  77. _enable_pin = hal.gpio->channel(_oe_pin_number);
  78. _enable_pin->mode(HAL_GPIO_OUTPUT);
  79. _enable_pin->write(0);
  80. }
  81. }
  82. void RCOutput_PCA9685::reset_all_channels()
  83. {
  84. if (!_dev->get_semaphore()->take(10)) {
  85. return;
  86. }
  87. uint8_t data[] = {PCA9685_RA_ALL_LED_ON_L, 0, 0, 0, 0};
  88. _dev->transfer(data, sizeof(data), nullptr, 0);
  89. /* Wait for the last pulse to end */
  90. hal.scheduler->delay(2);
  91. _dev->get_semaphore()->give();
  92. }
  93. void RCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
  94. {
  95. /* Correctly finish last pulses */
  96. for (int i = 0; i < (PWM_CHAN_COUNT - _channel_offset); i++) {
  97. write(i, _pulses_buffer[i]);
  98. }
  99. if (!_dev->get_semaphore()->take(10)) {
  100. return;
  101. }
  102. /* Shutdown before sleeping.
  103. * see p.14 of PCA9685 product datasheet
  104. */
  105. _dev->write_register(PCA9685_RA_ALL_LED_OFF_H, PCA9685_ALL_LED_OFF_H_SHUT);
  106. /* Put PCA9685 to sleep (required to write prescaler) */
  107. _dev->write_register(PCA9685_RA_MODE1, PCA9685_MODE1_SLEEP_BIT);
  108. /* Calculate prescale and save frequency using this value: it may be
  109. * different from @freq_hz due to rounding/ceiling. We use ceil() rather
  110. * than round() so the resulting frequency is never greater than @freq_hz
  111. */
  112. uint8_t prescale = ceilf(_osc_clock / (4096 * freq_hz)) - 1;
  113. _frequency = _osc_clock / (4096 * (prescale + 1));
  114. /* Write prescale value to match frequency */
  115. _dev->write_register(PCA9685_RA_PRE_SCALE, prescale);
  116. if (_external_clock) {
  117. /* Enable external clocking */
  118. _dev->write_register(PCA9685_RA_MODE1,
  119. PCA9685_MODE1_SLEEP_BIT | PCA9685_MODE1_EXTCLK_BIT);
  120. }
  121. /* Restart the device to apply new settings and enable auto-incremented write */
  122. _dev->write_register(PCA9685_RA_MODE1,
  123. PCA9685_MODE1_RESTART_BIT | PCA9685_MODE1_AI_BIT);
  124. _dev->get_semaphore()->give();
  125. }
  126. uint16_t RCOutput_PCA9685::get_freq(uint8_t ch)
  127. {
  128. return _frequency;
  129. }
  130. void RCOutput_PCA9685::enable_ch(uint8_t ch)
  131. {
  132. }
  133. void RCOutput_PCA9685::disable_ch(uint8_t ch)
  134. {
  135. write(ch, 0);
  136. }
  137. void RCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
  138. {
  139. if (ch >= (PWM_CHAN_COUNT - _channel_offset)) {
  140. return;
  141. }
  142. _pulses_buffer[ch] = period_us;
  143. _pending_write_mask |= (1U << ch);
  144. if (!_corking) {
  145. _corking = true;
  146. push();
  147. }
  148. }
  149. void RCOutput_PCA9685::cork()
  150. {
  151. _corking = true;
  152. }
  153. void RCOutput_PCA9685::push()
  154. {
  155. if (!_corking) {
  156. return;
  157. }
  158. _corking = false;
  159. if (_pending_write_mask == 0)
  160. return;
  161. // Calculate the number of channels for this transfer.
  162. uint8_t max_ch = (sizeof(unsigned) * 8) - __builtin_clz(_pending_write_mask);
  163. uint8_t min_ch = __builtin_ctz(_pending_write_mask);
  164. /*
  165. * scratch buffer size is always for all the channels, but we write only
  166. * from min_ch to max_ch
  167. */
  168. struct PACKED pwm_values {
  169. uint8_t reg;
  170. uint8_t data[PWM_CHAN_COUNT * 4];
  171. } pwm_values;
  172. for (unsigned ch = min_ch; ch < max_ch; ch++) {
  173. uint16_t period_us = _pulses_buffer[ch];
  174. uint16_t length = 0;
  175. if (period_us) {
  176. length = round((period_us * 4096) / (1000000.f / _frequency)) - 1;
  177. }
  178. uint8_t *d = &pwm_values.data[(ch - min_ch) * 4];
  179. *d++ = 0;
  180. *d++ = 0;
  181. *d++ = length & 0xFF;
  182. *d++ = length >> 8;
  183. }
  184. if (!_dev->get_semaphore()->take_nonblocking()) {
  185. return;
  186. }
  187. pwm_values.reg = PCA9685_RA_LED0_ON_L + 4 * (_channel_offset + min_ch);
  188. /* reg + all the channels we are going to write */
  189. size_t payload_size = 1 + (max_ch - min_ch) * 4;
  190. _dev->transfer((uint8_t *)&pwm_values, payload_size, nullptr, 0);
  191. _dev->get_semaphore()->give();
  192. _pending_write_mask = 0;
  193. }
  194. uint16_t RCOutput_PCA9685::read(uint8_t ch)
  195. {
  196. return _pulses_buffer[ch];
  197. }
  198. void RCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
  199. {
  200. for (int i = 0; i < len; i++) {
  201. period_us[i] = read(0 + i);
  202. }
  203. }