RCOutput_Bebop.cpp 15 KB

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