AP_RobotisServo.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. implementation of Robotis Dynamixel 2.0 protocol for controlling servos
  15. Portions of this code are based on the dynamixel_sdk code:
  16. https://github.com/ROBOTIS-GIT/DynamixelSDK
  17. which is under the following license:
  18. * Copyright 2017 ROBOTIS CO., LTD.
  19. *
  20. * Licensed under the Apache License, Version 2.0 (the "License");
  21. * you may not use this file except in compliance with the License.
  22. * You may obtain a copy of the License at
  23. *
  24. * http://www.apache.org/licenses/LICENSE-2.0
  25. *
  26. * Unless required by applicable law or agreed to in writing, software
  27. * distributed under the License is distributed on an "AS IS" BASIS,
  28. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  29. * See the License for the specific language governing permissions and
  30. * limitations under the License.
  31. */
  32. #include <AP_HAL/AP_HAL.h>
  33. #include <AP_Math/AP_Math.h>
  34. #include <AP_SerialManager/AP_SerialManager.h>
  35. #include <SRV_Channel/SRV_Channel.h>
  36. #include "AP_RobotisServo.h"
  37. extern const AP_HAL::HAL& hal;
  38. #define BROADCAST_ID 0xFE
  39. #define MAX_ID 0xFC
  40. // DXL protocol common commands
  41. #define INST_PING 1
  42. #define INST_READ 2
  43. #define INST_WRITE 3
  44. #define INST_REG_WRITE 4
  45. #define INST_ACTION 5
  46. #define INST_FACTORY_RESET 6
  47. #define INST_CLEAR 16
  48. #define INST_SYNC_WRITE 131
  49. #define INST_BULK_READ 146
  50. // 2.0 protocol commands
  51. #define INST_REBOOT 8
  52. #define INST_STATUS 85
  53. #define INST_SYNC_READ 130
  54. #define INST_BULK_WRITE 147
  55. // 2.0 protocol packet offsets
  56. #define PKT_HEADER0 0
  57. #define PKT_HEADER1 1
  58. #define PKT_HEADER2 2
  59. #define PKT_RESERVED 3
  60. #define PKT_ID 4
  61. #define PKT_LENGTH_L 5
  62. #define PKT_LENGTH_H 6
  63. #define PKT_INSTRUCTION 7
  64. #define PKT_ERROR 8
  65. #define PKT_PARAMETER0 8
  66. /* Macro for Control Table Value */
  67. #define DXL_MAKEWORD(a, b) ((uint16_t)(((uint8_t)(((uint64_t)(a)) & 0xff)) | ((uint16_t)((uint8_t)(((uint64_t)(b)) & 0xff))) << 8))
  68. #define DXL_MAKEDWORD(a, b) ((uint32_t)(((uint16_t)(((uint64_t)(a)) & 0xffff)) | ((uint32_t)((uint16_t)(((uint64_t)(b)) & 0xffff))) << 16))
  69. #define DXL_LOWORD(l) ((uint16_t)(((uint64_t)(l)) & 0xffff))
  70. #define DXL_HIWORD(l) ((uint16_t)((((uint64_t)(l)) >> 16) & 0xffff))
  71. #define DXL_LOBYTE(w) ((uint8_t)(((uint64_t)(w)) & 0xff))
  72. #define DXL_HIBYTE(w) ((uint8_t)((((uint64_t)(w)) >> 8) & 0xff))
  73. // register offsets
  74. #define REG_OPERATING_MODE 11
  75. #define OPMODE_CURR_CONTROL 0
  76. #define OPMODE_VEL_CONTROL 1
  77. #define OPMODE_POS_CONTROL 3
  78. #define OPMODE_EXT_POS_CONTROL 4
  79. #define REG_TORQUE_ENABLE 64
  80. #define REG_STATUS_RETURN 68
  81. #define STATUS_RETURN_NONE 0
  82. #define STATUS_RETURN_READ 1
  83. #define STATUS_RETURN_ALL 2
  84. #define REG_GOAL_POSITION 116
  85. // how many times to send servo configure msgs
  86. #define CONFIGURE_SERVO_COUNT 4
  87. // how many times to send servo detection
  88. #define DETECT_SERVO_COUNT 4
  89. const AP_Param::GroupInfo AP_RobotisServo::var_info[] = {
  90. // @Param: POSMIN
  91. // @DisplayName: Robotis servo position min
  92. // @Description: Position minimum at servo min value. This should be within the position control range of the servos, normally 0 to 4095
  93. // @Range: 0 4095
  94. // @User: Standard
  95. AP_GROUPINFO("POSMIN", 1, AP_RobotisServo, pos_min, 0),
  96. // @Param: POSMAX
  97. // @DisplayName: Robotis servo position max
  98. // @Description: Position maximum at servo max value. This should be within the position control range of the servos, normally 0 to 4095
  99. // @Range: 0 4095
  100. // @User: Standard
  101. AP_GROUPINFO("POSMAX", 2, AP_RobotisServo, pos_max, 4095),
  102. AP_GROUPEND
  103. };
  104. // constructor
  105. AP_RobotisServo::AP_RobotisServo(void)
  106. {
  107. // set defaults from the parameter table
  108. AP_Param::setup_object_defaults(this, var_info);
  109. }
  110. void AP_RobotisServo::init(void)
  111. {
  112. AP_SerialManager &serial_manager = AP::serialmanager();
  113. port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Robotis,0);
  114. if (port) {
  115. baudrate = serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Robotis, 0);
  116. us_per_byte = 10 * 1e6 / baudrate;
  117. us_gap = 4 * 1e6 / baudrate;
  118. }
  119. }
  120. /*
  121. calculate Robotis protocol CRC
  122. */
  123. uint16_t AP_RobotisServo::update_crc(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size)
  124. {
  125. uint16_t i;
  126. static const uint16_t crc_table[256] = {0x0000,
  127. 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011,
  128. 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027,
  129. 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D,
  130. 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A, 0x804B,
  131. 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC, 0x80C9,
  132. 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5, 0x80FF,
  133. 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0, 0x80A5,
  134. 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1, 0x8093,
  135. 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082,
  136. 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197,
  137. 0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE,
  138. 0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB,
  139. 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC, 0x81D9,
  140. 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145, 0x814F,
  141. 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173, 0x0176,
  142. 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162, 0x8123,
  143. 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132,
  144. 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104,
  145. 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D,
  146. 0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A, 0x832B,
  147. 0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F, 0x036A,
  148. 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356, 0x035C,
  149. 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0, 0x83C5,
  150. 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1, 0x83F3,
  151. 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2,
  152. 0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7,
  153. 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E,
  154. 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A, 0x829B,
  155. 0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC, 0x82B9,
  156. 0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6, 0x02EC,
  157. 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0, 0x82D5,
  158. 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1, 0x8243,
  159. 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252,
  160. 0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264,
  161. 0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E,
  162. 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219, 0x0208,
  163. 0x820D, 0x8207, 0x0202 };
  164. for (uint16_t j = 0; j < data_blk_size; j++) {
  165. i = ((uint16_t)(crc_accum >> 8) ^ *data_blk_ptr++) & 0xFF;
  166. crc_accum = (crc_accum << 8) ^ crc_table[i];
  167. }
  168. return crc_accum;
  169. }
  170. /*
  171. addStuffing() from Robotis SDK. This pads the packet as required by the protocol
  172. */
  173. void AP_RobotisServo::add_stuffing(uint8_t *packet)
  174. {
  175. int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]);
  176. int packet_length_out = packet_length_in;
  177. if (packet_length_in < 8) {
  178. // INSTRUCTION, ADDR_L, ADDR_H, CRC16_L, CRC16_H + FF FF FD
  179. return;
  180. }
  181. uint8_t *packet_ptr;
  182. uint16_t packet_length_before_crc = packet_length_in - 2;
  183. for (uint16_t i = 3; i < packet_length_before_crc; i++) {
  184. packet_ptr = &packet[i+PKT_INSTRUCTION-2];
  185. if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD) {
  186. packet_length_out++;
  187. }
  188. }
  189. if (packet_length_in == packet_length_out) {
  190. // no stuffing required
  191. return;
  192. }
  193. uint16_t out_index = packet_length_out + 6 - 2; // last index before crc
  194. uint16_t in_index = packet_length_in + 6 - 2; // last index before crc
  195. while (out_index != in_index) {
  196. if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF) {
  197. packet[out_index--] = 0xFD; // byte stuffing
  198. if (out_index != in_index) {
  199. packet[out_index--] = packet[in_index--]; // FD
  200. packet[out_index--] = packet[in_index--]; // FF
  201. packet[out_index--] = packet[in_index--]; // FF
  202. }
  203. } else {
  204. packet[out_index--] = packet[in_index--];
  205. }
  206. }
  207. packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out);
  208. packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out);
  209. }
  210. /*
  211. send a protocol 2.0 packet
  212. */
  213. void AP_RobotisServo::send_packet(uint8_t *txpacket)
  214. {
  215. add_stuffing(txpacket);
  216. // check max packet length
  217. uint16_t total_packet_length = DXL_MAKEWORD(txpacket[PKT_LENGTH_L], txpacket[PKT_LENGTH_H]) + 7;
  218. // make packet header
  219. txpacket[PKT_HEADER0] = 0xFF;
  220. txpacket[PKT_HEADER1] = 0xFF;
  221. txpacket[PKT_HEADER2] = 0xFD;
  222. txpacket[PKT_RESERVED] = 0x00;
  223. // add CRC16
  224. uint16_t crc = update_crc(0, txpacket, total_packet_length - 2); // 2: CRC16
  225. txpacket[total_packet_length - 2] = DXL_LOBYTE(crc);
  226. txpacket[total_packet_length - 1] = DXL_HIBYTE(crc);
  227. port->write(txpacket, total_packet_length);
  228. delay_time_us += total_packet_length * us_per_byte + us_gap;
  229. }
  230. /*
  231. use a broadcast ping to find attached servos
  232. */
  233. void AP_RobotisServo::detect_servos(void)
  234. {
  235. uint8_t txpacket[10] {};
  236. txpacket[PKT_ID] = BROADCAST_ID;
  237. txpacket[PKT_LENGTH_L] = 3;
  238. txpacket[PKT_LENGTH_H] = 0;
  239. txpacket[PKT_INSTRUCTION] = INST_PING;
  240. send_packet(txpacket);
  241. // give plenty of time for replies from all servos
  242. last_send_us = AP_HAL::micros();
  243. delay_time_us += 1000 * us_per_byte;
  244. }
  245. /*
  246. broadcast configure all servos
  247. */
  248. void AP_RobotisServo::configure_servos(void)
  249. {
  250. // disable torque control
  251. send_command(BROADCAST_ID, REG_TORQUE_ENABLE, 0, 1);
  252. // disable replies unless we read
  253. send_command(BROADCAST_ID, REG_STATUS_RETURN, STATUS_RETURN_READ, 1);
  254. // use position control mode
  255. send_command(BROADCAST_ID, REG_OPERATING_MODE, OPMODE_POS_CONTROL, 1);
  256. // enable torque control
  257. send_command(BROADCAST_ID, REG_TORQUE_ENABLE, 1, 1);
  258. }
  259. /*
  260. send a command to a single servo, changing a register value
  261. */
  262. void AP_RobotisServo::send_command(uint8_t id, uint16_t reg, uint32_t value, uint8_t len)
  263. {
  264. uint8_t txpacket[16] {};
  265. txpacket[PKT_ID] = id;
  266. txpacket[PKT_LENGTH_L] = 5 + len;
  267. txpacket[PKT_LENGTH_H] = 0;
  268. txpacket[PKT_INSTRUCTION] = INST_WRITE;
  269. txpacket[PKT_INSTRUCTION+1] = DXL_LOBYTE(reg);
  270. txpacket[PKT_INSTRUCTION+2] = DXL_HIBYTE(reg);
  271. memcpy(&txpacket[PKT_INSTRUCTION+3], &value, MIN(len,4));
  272. send_packet(txpacket);
  273. }
  274. /*
  275. read response bytes
  276. */
  277. void AP_RobotisServo::read_bytes(void)
  278. {
  279. uint32_t n = port->available();
  280. if (n == 0 && pktbuf_ofs < PKT_INSTRUCTION) {
  281. return;
  282. }
  283. if (n > sizeof(pktbuf) - pktbuf_ofs) {
  284. n = sizeof(pktbuf) - pktbuf_ofs;
  285. }
  286. for (uint8_t i=0; i<n; i++) {
  287. pktbuf[pktbuf_ofs++] = port->read();
  288. }
  289. // discard bad leading data. This should be rare
  290. while (pktbuf_ofs >= 4 &&
  291. (pktbuf[0] != 0xFF || pktbuf[1] != 0xFF || pktbuf[2] != 0xFD || pktbuf[3] != 0x00)) {
  292. memmove(pktbuf, &pktbuf[1], pktbuf_ofs-1);
  293. pktbuf_ofs--;
  294. }
  295. if (pktbuf_ofs < 10) {
  296. // not enough data yet
  297. return;
  298. }
  299. const uint16_t total_packet_length = DXL_MAKEWORD(pktbuf[PKT_LENGTH_L], pktbuf[PKT_LENGTH_H]) + PKT_INSTRUCTION;
  300. if (total_packet_length > sizeof(pktbuf)) {
  301. pktbuf_ofs = 0;
  302. return;
  303. }
  304. if (pktbuf_ofs < total_packet_length) {
  305. // more data needed
  306. return;
  307. }
  308. // check CRC
  309. const uint16_t crc = DXL_MAKEWORD(pktbuf[total_packet_length-2], pktbuf[total_packet_length-1]);
  310. const uint16_t calc_crc = update_crc(0, pktbuf, total_packet_length - 2);
  311. if (calc_crc != crc) {
  312. memmove(pktbuf, &pktbuf[total_packet_length], pktbuf_ofs - total_packet_length);
  313. pktbuf_ofs -= total_packet_length;
  314. return;
  315. }
  316. // process full packet
  317. process_packet(pktbuf, total_packet_length);
  318. memmove(pktbuf, &pktbuf[total_packet_length], pktbuf_ofs - total_packet_length);
  319. pktbuf_ofs -= total_packet_length;
  320. }
  321. /*
  322. process a packet from a servo
  323. */
  324. void AP_RobotisServo::process_packet(const uint8_t *pkt, uint8_t length)
  325. {
  326. uint8_t id = pkt[PKT_ID];
  327. if (id > 16 || id < 1) {
  328. // discard packets from servos beyond max or min. Note that we
  329. // don't allow servo 0, to make mapping to SERVOn_* parameters
  330. // easier
  331. return;
  332. }
  333. uint16_t id_mask = (1U<<(id-1));
  334. if (!(id_mask & servo_mask)) {
  335. // mark the servo as present
  336. servo_mask |= id_mask;
  337. hal.console->printf("Robotis: new servo %u\n", id);
  338. }
  339. }
  340. void AP_RobotisServo::update()
  341. {
  342. if (!initialised) {
  343. initialised = true;
  344. init();
  345. last_send_us = AP_HAL::micros();
  346. return;
  347. }
  348. if (port == nullptr) {
  349. return;
  350. }
  351. read_bytes();
  352. uint32_t now = AP_HAL::micros();
  353. if (last_send_us != 0 && now - last_send_us < delay_time_us) {
  354. // waiting for last send to complete
  355. return;
  356. }
  357. if (detection_count < DETECT_SERVO_COUNT) {
  358. detection_count++;
  359. detect_servos();
  360. }
  361. if (servo_mask == 0) {
  362. return;
  363. }
  364. if (configured_servos < CONFIGURE_SERVO_COUNT) {
  365. configured_servos++;
  366. last_send_us = now;
  367. configure_servos();
  368. return;
  369. }
  370. last_send_us = now;
  371. delay_time_us = 0;
  372. // loop for all 16 channels
  373. for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
  374. if (((1U<<i) & servo_mask) == 0) {
  375. continue;
  376. }
  377. SRV_Channel *c = SRV_Channels::srv_channel(i);
  378. if (c == nullptr) {
  379. continue;
  380. }
  381. const uint16_t pwm = c->get_output_pwm();
  382. const uint16_t min = c->get_output_min();
  383. const uint16_t max = c->get_output_max();
  384. float v = float(pwm - min) / (max - min);
  385. uint32_t value = pos_min + v * (pos_max - pos_min);
  386. send_command(i+1, REG_GOAL_POSITION, value, 4);
  387. }
  388. }