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