APM:Libraries
RCOutput_Bebop.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
4 #include "RCOutput_Bebop.h"
5 
6 #include <errno.h>
7 #include <poll.h>
8 #include <pthread.h>
9 #include <stdio.h>
10 #include <stdlib.h>
11 #include <sys/mman.h>
12 #include <sys/time.h>
13 #include <unistd.h>
14 #include <utility>
15 
17 #include <AP_Math/AP_Math.h>
18 
19 #include "Util.h"
20 
21 /* BEBOP BLDC registers description */
22 #define BEBOP_BLDC_I2C_ADDR 0x08
23 #define BEBOP_BLDC_STARTPROP 0x40
24 #define BEBOP_BLDC_SETREFSPEED 0x02
25 
26 #define BEBOP_BLDC_GETOBSDATA 0x20
27 
28 struct PACKED bldc_info {
29  uint8_t version_maj;
30  uint8_t version_min;
31  uint8_t type;
32  uint8_t n_motors;
33  uint16_t n_flights;
34  uint16_t last_flight_time;
36  uint8_t last_error;
37 };
38 
39 #define BEBOP_BLDC_TOGGLE_GPIO 0x4d
40 #define BEBOP_BLDC_GPIO_0 (1 << 0)
41 #define BEBOP_BLDC_GPIO_1 (1 << 1)
42 #define BEBOP_BLDC_GPIO_2 (1 << 2)
43 #define BEBOP_BLDC_GPIO_3 (1 << 3)
44 #define BEBOP_BLDC_GPIO_POWER (1 << 4)
45 
46 #define BEBOP_BLDC_STOP_PROP 0x60
47 
48 #define BEBOP_BLDC_CLEAR_ERROR 0x80
49 
50 #define BEBOP_BLDC_PLAY_SOUND 0x82
51 
52 #define BEBOP_BLDC_GET_INFO 0xA0
53 
54 #define BEBOP_BLDC_MIN_PERIOD_US 1100
55 #define BEBOP_BLDC_MAX_PERIOD_US 1900
56 #define BEBOP_BLDC_MIN_RPM 1000
57 /* the max rpm speed is different on Bebop 2 */
58 #define BEBOP_BLDC_MAX_RPM_1 11000
59 #define BEBOP_BLDC_MAX_RPM_2 12200
60 #define BEBOP_BLDC_MAX_RPM_DISCO 12500
61 
62 /* Priority of the thread controlling the BLDC via i2c
63  * set to 14, which is the same as the UART
64  */
65 #define RCOUT_BEBOP_RTPRIO 14
66 /* Set timeout to 500ms */
67 #define BEBOP_BLDC_TIMEOUT_NS 500000000
68 
69 enum {
72 };
73 
74 /* values of bottom nibble of the obs data status byte */
80 };
81 
82 using namespace Linux;
83 
84 static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
85 
86 RCOutput_Bebop::RCOutput_Bebop(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
87  : _dev(std::move(dev))
88  , _min_pwm(BEBOP_BLDC_MIN_PERIOD_US)
89  , _max_pwm(BEBOP_BLDC_MAX_PERIOD_US)
90  , _state(BEBOP_BLDC_STOPPED)
91 {
92  memset(_period_us, 0, sizeof(_period_us));
93  memset(_request_period_us, 0, sizeof(_request_period_us));
94  memset(_rpm, 0, sizeof(_rpm));
95 }
96 
97 uint8_t RCOutput_Bebop::_checksum(uint8_t *data, unsigned int len)
98 {
99  uint8_t checksum = data[0];
100  unsigned int i;
101 
102  for (i = 1; i < len; i++)
103  checksum = checksum ^ data[i];
104 
105  return checksum;
106 }
107 
109 {
110  uint8_t data = BEBOP_BLDC_STARTPROP;
111 
113  return;
114  }
115 
116  if (_dev->transfer(&data, sizeof(data), nullptr, 0)) {
118  }
119  _dev->get_semaphore()->give();
120 }
121 
123 {
124  struct PACKED bldc_ref_speed_data {
125  uint8_t cmd;
126  uint16_t rpm[BEBOP_BLDC_MOTORS_NUM];
127  uint8_t enable_security;
128  uint8_t checksum;
129  } data {};
130  int i;
131 
132  data.cmd = BEBOP_BLDC_SETREFSPEED;
133 
134  for (i=0; i<BEBOP_BLDC_MOTORS_NUM; i++) {
135  data.rpm[i] = htobe16(rpm[i]);
136  }
137 
138  data.enable_security = 0;
139  data.checksum = _checksum((uint8_t *) &data, sizeof(data) - 1);
140 
142  return;
143  }
144 
145  _dev->transfer((uint8_t *)&data, sizeof(data), nullptr, 0);
146 
147  _dev->get_semaphore()->give();
148 }
149 
151 {
152  if (info == nullptr) {
153  return false;
154  }
155 
156  memset(info, 0, sizeof(struct bldc_info));
157 
159  return false;
160  }
161  _dev->read_registers(BEBOP_BLDC_GET_INFO, (uint8_t*)info, sizeof(*info));
162  _dev->get_semaphore()->give();
163  return true;
164 }
165 
167 {
168  /*
169  the structure returned is different on the Disco from the Bebop
170  */
171  struct PACKED bldc_obs_data {
172  uint16_t rpm[BEBOP_BLDC_MOTORS_NUM];
173  uint16_t batt_mv;
174  uint8_t status;
175  uint8_t error;
176  uint8_t motors_err;
177  uint8_t temp;
178 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
179  /*
180  bit 0 indicates an overcurrent on the RC receiver port when high
181  bits #1-#6 indicate an overcurrent on the #1-#6 PPM servos
182  */
183  uint8_t overcurrent;
184 #endif
185  uint8_t checksum;
186  } data;
187 
188  memset(&data, 0, sizeof(data));
190  return -EBUSY;
191  }
192 
193  _dev->read_registers(BEBOP_BLDC_GETOBSDATA, (uint8_t *)&data, sizeof(data));
194  _dev->get_semaphore()->give();
195 
196  if (data.checksum != _checksum((uint8_t*)&data, sizeof(data)-1)) {
197  return -EBUSY;
198  }
199 
200  memset(&obs, 0, sizeof(obs));
201 
202  /* fill obs class */
203  for (uint8_t i = 0; i < _n_motors; i++) {
204  /* extract 'rpm saturation bit' */
205  obs.rpm_saturated[i] = (data.rpm[i] & (1 << 7)) ? 1 : 0;
206  /* clear 'rpm saturation bit' */
207  data.rpm[i] &= (uint16_t)(~(1 << 7));
208  obs.rpm[i] = be16toh(data.rpm[i]);
209  if (obs.rpm[i] == 0) {
210  obs.rpm_saturated[i] = 0;
211  }
212 #if 0
213  printf("rpm %u %u %u %u status 0x%02x temp %u\n",
214  obs.rpm[i], _rpm[0], _period_us[0], _period_us_to_rpm(_period_us[0]),
215  (unsigned)data.status,
216  (unsigned)data.temp);
217 #endif
218  }
219 
220  // sync our state from status. This makes us more robust to i2c errors
221  enum BLDC_STATUS bldc_status = (enum BLDC_STATUS)(data.status & 0x0F);
222  switch (bldc_status) {
226  break;
230  break;
231  }
232 
233  obs.batt_mv = be16toh(data.batt_mv);
234  obs.status = data.status;
235  obs.error = data.error;
236  obs.motors_err = data.motors_err;
237  obs.temperature = data.temp;
238 
239  return 0;
240 }
241 
243 {
245  return;
246  }
247 
249  _dev->get_semaphore()->give();
250 }
251 
253 {
254  uint8_t data = BEBOP_BLDC_STOP_PROP;
255 
257  return;
258  }
259 
260  _dev->transfer(&data, sizeof(data), nullptr, 0);
261  _dev->get_semaphore()->give();
262 }
263 
265 {
266  uint8_t data = BEBOP_BLDC_CLEAR_ERROR;
267 
269  return;
270  }
271 
272  _dev->transfer(&data, sizeof(data), nullptr, 0);
273  _dev->get_semaphore()->give();
274 }
275 
276 void RCOutput_Bebop::_play_sound(uint8_t sound)
277 {
279  return;
280  }
281 
283  _dev->get_semaphore()->give();
284 }
285 
286 /*
287  * pwm is the pwm power used for the note.
288  * It has to be >= 3, otherwise it refers to a predefined song
289  * (see _play_sound function)
290  * period is in us and duration in ms.
291  */
293  uint16_t period_us,
294  uint16_t duration_ms)
295 {
296  struct PACKED {
297  uint8_t header;
298  uint8_t pwm;
299  be16_t period;
300  be16_t duration;
301  } msg;
302 
303  if (pwm < 3) {
304  return;
305  }
306 
307  msg.header = BEBOP_BLDC_PLAY_SOUND;
308  msg.pwm = pwm;
309  msg.period = htobe16(period_us);
310  msg.duration = htobe16(duration_ms);
311 
313  return;
314  }
315 
316  _dev->transfer((uint8_t *)&msg, sizeof(msg), nullptr, 0);
317  _dev->get_semaphore()->give();
318 }
319 
320 uint16_t RCOutput_Bebop::_period_us_to_rpm(uint16_t period_us)
321 {
322  period_us = constrain_int16(period_us, _min_pwm, _max_pwm);
323  float period_us_fl = period_us;
324  float rpm_fl = (period_us_fl - _min_pwm)/(_max_pwm - _min_pwm) *
326 
327  return (uint16_t)rpm_fl;
328 }
329 
331 {
332  int ret=0;
333  struct sched_param param = { .sched_priority = RCOUT_BEBOP_RTPRIO };
334  pthread_attr_t attr;
335  pthread_condattr_t cond_attr;
336 
337  /* Initialize thread, cond, and mutex */
338  ret = pthread_mutex_init(&_mutex, nullptr);
339  if (ret != 0) {
340  perror("RCout_Bebop: failed to init mutex\n");
341  return;
342  }
343 
344  pthread_mutex_lock(&_mutex);
345 
346  pthread_condattr_init(&cond_attr);
347  pthread_condattr_setclock(&cond_attr, CLOCK_MONOTONIC);
348  ret = pthread_cond_init(&_cond, &cond_attr);
349  pthread_condattr_destroy(&cond_attr);
350  if (ret != 0) {
351  perror("RCout_Bebop: failed to init cond\n");
352  goto exit;
353  }
354 
355  ret = pthread_attr_init(&attr);
356  if (ret != 0) {
357  perror("RCOut_Bebop: failed to init attr\n");
358  goto exit;
359  }
360  pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
361  pthread_attr_setschedpolicy(&attr, SCHED_FIFO);
362  pthread_attr_setschedparam(&attr, &param);
363  ret = pthread_create(&_thread, &attr, _control_thread, this);
364  if (ret != 0) {
365  perror("RCOut_Bebop: failed to create thread\n");
366  goto exit;
367  }
368 
369  _clear_error();
370 
371  /* Set an initial dummy frequency */
372  _frequency = 50;
373 
374  // enable servo power (also receiver power)
376 
377 exit:
378  pthread_mutex_unlock(&_mutex);
379  return;
380 }
381 
382 void RCOutput_Bebop::set_freq(uint32_t chmask, uint16_t freq_hz)
383 {
384  _frequency = freq_hz;
385 }
386 
387 uint16_t RCOutput_Bebop::get_freq(uint8_t ch)
388 {
389  return _frequency;
390 }
391 
393 {
394 }
395 
397 {
398  _stop_prop();
399 }
400 
401 void RCOutput_Bebop::write(uint8_t ch, uint16_t period_us)
402 {
403  if (ch >= BEBOP_BLDC_MOTORS_NUM) {
404  return;
405  }
406 
407  _request_period_us[ch] = period_us;
408 
409  if (!_corking) {
410  push();
411  }
412 }
413 
415 {
416  _corking = true;
417 }
418 
420 {
421  if (!_corking) {
422  return;
423  }
424  _corking = false;
425  pthread_mutex_lock(&_mutex);
426  memcpy(_period_us, _request_period_us, sizeof(_period_us));
427  pthread_cond_signal(&_cond);
428  pthread_mutex_unlock(&_mutex);
429  memset(_request_period_us, 0, sizeof(_request_period_us));
430 }
431 
432 uint16_t RCOutput_Bebop::read(uint8_t ch)
433 {
434  if (ch < BEBOP_BLDC_MOTORS_NUM) {
435  return _period_us[ch];
436  } else {
437  return 0;
438  }
439 }
440 
441 void RCOutput_Bebop::read(uint16_t* period_us, uint8_t len)
442 {
443  for (int i = 0; i < len; i++) {
444  period_us[i] = read(0 + i);
445  }
446 }
447 
448 void RCOutput_Bebop::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
449 {
450  _min_pwm = min_pwm;
451  _max_pwm = max_pwm;
452 }
453 
454 /* Separate thread to handle the Bebop motors controller */
456  RCOutput_Bebop* rcout = (RCOutput_Bebop *) arg;
457 
458  rcout->_run_rcout();
459  return nullptr;
460 }
461 
463 {
464  uint16_t current_period_us[BEBOP_BLDC_MOTORS_NUM];
465  uint8_t i;
466  int ret;
467  struct timespec ts;
468  struct bldc_info info;
469  uint8_t bebop_bldc_channels[BEBOP_BLDC_MOTORS_NUM] {};
470  int hw_version;
471 
472  memset(current_period_us, 0, sizeof(current_period_us));
473 
474  if (!_get_info(&info)) {
475  AP_HAL::panic("failed to get BLDC info");
476  }
477 
478  // remember _n_motors for read_obs_data()
479  _n_motors = info.n_motors;
480 
481 #if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_DISCO
482  uint8_t bebop_bldc_right_front, bebop_bldc_left_front,
483  bebop_bldc_left_back, bebop_bldc_right_back;
484  /* Set motor order depending on BLDC version.On bebop 1 with version 1
485  * keep current order. The order changes from version 2 on bebop 1 and
486  * remains the same as this for bebop 2
487  */
488  if (info.version_maj == 1) {
489  bebop_bldc_right_front = BEBOP_BLDC_MOTOR_1;
490  bebop_bldc_left_front = BEBOP_BLDC_MOTOR_2;
491  bebop_bldc_left_back = BEBOP_BLDC_MOTOR_3;
492  bebop_bldc_right_back = BEBOP_BLDC_MOTOR_4;
493  } else {
494  bebop_bldc_right_front = BEBOP_BLDC_MOTOR_2;
495  bebop_bldc_left_front = BEBOP_BLDC_MOTOR_1;
496  bebop_bldc_left_back = BEBOP_BLDC_MOTOR_4;
497  bebop_bldc_right_back = BEBOP_BLDC_MOTOR_3;
498  }
499 
500  bebop_bldc_channels[0] = bebop_bldc_right_front;
501  bebop_bldc_channels[1] = bebop_bldc_left_back;
502  bebop_bldc_channels[2] = bebop_bldc_left_front;
503  bebop_bldc_channels[3] = bebop_bldc_right_back;
504 #endif
505 
506  hw_version = Util::from(hal.util)->get_hw_arm32();
507  if (hw_version == UTIL_HARDWARE_BEBOP) {
509  } else if (hw_version == UTIL_HARDWARE_BEBOP2) {
511  } else if (hw_version == UTIL_HARDWARE_DISCO) {
513  } else if (hw_version < 0) {
514  AP_HAL::panic("failed to get hw version %s", strerror(hw_version));
515  } else {
516  AP_HAL::panic("unsupported hw version %d", hw_version);
517  }
518  printf("Bebop: vers %u/%u type %u nmotors %u n_flights %u last_flight_time %u total_flight_time %u maxrpm %u\n",
519  (unsigned)info.version_maj, (unsigned)info.version_min, (unsigned)info.type,
520  (unsigned)info.n_motors, (unsigned)be16toh(info.n_flights),
521  (unsigned)be16toh(info.last_flight_time), (unsigned)be32toh(info.total_flight_time),
522  (unsigned)_max_rpm);
523 
524  while (true) {
525  pthread_mutex_lock(&_mutex);
526  ret = clock_gettime(CLOCK_MONOTONIC, &ts);
527  if (ret != 0) {
528  pthread_mutex_unlock(&_mutex);
529  continue;
530  }
531 
532  if (ts.tv_nsec > (1000000000 - BEBOP_BLDC_TIMEOUT_NS)) {
533  ts.tv_sec += 1;
534  ts.tv_nsec = ts.tv_nsec + BEBOP_BLDC_TIMEOUT_NS - 1000000000;
535  } else {
536  ts.tv_nsec += BEBOP_BLDC_TIMEOUT_NS;
537  }
538 
539  ret = 0;
540  while ((memcmp(_period_us, current_period_us, sizeof(_period_us)) == 0) && (ret == 0)) {
541  ret = pthread_cond_timedwait(&_cond, &_mutex, &ts);
542  }
543 
544  memcpy(current_period_us, _period_us, sizeof(_period_us));
545  pthread_mutex_unlock(&_mutex);
546 
547  /* start propellers if the speed of the 4 motors is >= min speed
548  * min speed set to min_pwm + 50*/
549  for (i = 0; i < _n_motors; i++) {
550  if (current_period_us[i] <= _min_pwm + 50) {
551  break;
552  }
553  _rpm[bebop_bldc_channels[i]] = _period_us_to_rpm(current_period_us[i]);
554  }
555 
556  if (i < _n_motors) {
557  /* one motor pwm value is at minimum (or under)
558  * if the motors are started, stop them*/
559  if (_state == BEBOP_BLDC_STARTED) {
560  _stop_prop();
561  _clear_error();
562  }
563  } else {
564  /* all the motor pwm values are higher than minimum
565  * if the bldc is stopped, start it*/
566  if (_state == BEBOP_BLDC_STOPPED) {
567  _start_prop();
568  }
570  }
571  }
572 }
573 
574 #endif
uint16_t last_flight_time
int printf(const char *fmt,...)
Definition: stdio.c:113
static uint32_t be32toh(be32_t value)
Definition: sparse-endian.h:84
uint8_t type
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
#define BEBOP_BLDC_SETREFSPEED
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
#define BEBOP_BLDC_PLAY_SOUND
#define BEBOP_BLDC_STOP_PROP
pthread_cond_t _cond
int read_obs_data(BebopBLDC_ObsData &data)
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
#define BEBOP_BLDC_MAX_RPM_DISCO
virtual Semaphore * get_semaphore() override=0
#define BEBOP_BLDC_GETOBSDATA
bool _get_info(struct bldc_info *info)
AP_HAL::Util * util
Definition: HAL.h:115
uint16_t read(uint8_t ch) override
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
static uint16_t pwm
Definition: RCOutput.cpp:20
uint8_t version_min
#define BEBOP_BLDC_CLEAR_ERROR
#define BEBOP_BLDC_TIMEOUT_NS
#define BEBOP_BLDC_TOGGLE_GPIO
uint16_t _rpm[BEBOP_BLDC_MOTORS_NUM]
#define BEBOP_BLDC_GPIO_POWER
uint16_t get_freq(uint8_t ch) override
#define BEBOP_BLDC_GET_INFO
uint8_t rpm_saturated[BEBOP_BLDC_MOTORS_NUM]
void enable_ch(uint8_t ch) override
static Util * from(AP_HAL::Util *util)
Definition: Util.h:27
uint16_t _request_period_us[BEBOP_BLDC_MOTORS_NUM]
uint16_t _period_us_to_rpm(uint16_t period_us)
void perror(const char *s)
POSIX perror() - convert POSIX errno to text with user message.
Definition: posix.c:1827
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
uint16_t _period_us[BEBOP_BLDC_MOTORS_NUM]
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void _set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM])
void disable_ch(uint8_t ch) override
#define BEBOP_BLDC_MAX_RPM_1
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
#define RCOUT_BEBOP_RTPRIO
uint16_t n_flights
static be16_t htobe16(uint16_t value)
Definition: sparse-endian.h:75
virtual bool give()=0
uint8_t last_error
void _toggle_gpio(uint8_t mask)
const HAL & get_HAL()
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]
static const AP_HAL::HAL & hal
#define BEBOP_BLDC_MAX_PERIOD_US
BLDC_STATUS
#define BEBOP_BLDC_STARTPROP
#define BEBOP_BLDC_GPIO_2
uint8_t n_motors
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
static void * _control_thread(void *arg)
#define error(fmt, args ...)
#define PACKED
Definition: AP_Common.h:28
uint8_t _checksum(uint8_t *data, unsigned int len)
uint32_t total_flight_time
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
void set_freq(uint32_t chmask, uint16_t freq_hz) override
pthread_mutex_t _mutex
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define BEBOP_BLDC_MAX_RPM_2
void write(uint8_t ch, uint16_t period_us) override
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void _play_sound(uint8_t sound)
#define BEBOP_BLDC_MIN_PERIOD_US
uint8_t version_maj
int get_hw_arm32()
Definition: Util.cpp:185
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36
void play_note(uint8_t pwm, uint16_t period_us, uint16_t duration_ms)
#define BEBOP_BLDC_MIN_RPM