protocol2_packet_handler.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Author: zerom, Ryu Woon Jung (Leon) */
18 
19 #if defined(__linux__)
20 #include <unistd.h>
22 #elif defined(__APPLE__)
23 #include <unistd.h>
25 #elif defined(_WIN32) || defined(_WIN64)
26 #define WINDLLEXPORT
27 #include <Windows.h>
29 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
30 #include "../../include/dynamixel_sdk/protocol2_packet_handler.h"
31 #endif
32 
33 #include <stdio.h>
34 #include <string.h>
35 #include <stdlib.h>
36 
37 #define TXPACKET_MAX_LEN (1*1024)
38 #define RXPACKET_MAX_LEN (1*1024)
39 
41 #define PKT_HEADER0 0
42 #define PKT_HEADER1 1
43 #define PKT_HEADER2 2
44 #define PKT_RESERVED 3
45 #define PKT_ID 4
46 #define PKT_LENGTH_L 5
47 #define PKT_LENGTH_H 6
48 #define PKT_INSTRUCTION 7
49 #define PKT_ERROR 8
50 #define PKT_PARAMETER0 8
51 
53 #define ERRNUM_RESULT_FAIL 1 // Failed to process the instruction packet.
54 #define ERRNUM_INSTRUCTION 2 // Instruction error
55 #define ERRNUM_CRC 3 // CRC check error
56 #define ERRNUM_DATA_RANGE 4 // Data range error
57 #define ERRNUM_DATA_LENGTH 5 // Data length error
58 #define ERRNUM_DATA_LIMIT 6 // Data limit error
59 #define ERRNUM_ACCESS 7 // Access error
60 
61 #define ERRBIT_ALERT 128 //When the device has a problem, this bit is set to 1. Check "Device Status Check" value.
62 
63 using namespace dynamixel;
64 
66 
68 
70 {
71  switch(result)
72  {
73  case COMM_SUCCESS:
74  return "[TxRxResult] Communication success.";
75 
76  case COMM_PORT_BUSY:
77  return "[TxRxResult] Port is in use!";
78 
79  case COMM_TX_FAIL:
80  return "[TxRxResult] Failed transmit instruction packet!";
81 
82  case COMM_RX_FAIL:
83  return "[TxRxResult] Failed get status packet from device!";
84 
85  case COMM_TX_ERROR:
86  return "[TxRxResult] Incorrect instruction packet!";
87 
88  case COMM_RX_WAITING:
89  return "[TxRxResult] Now recieving status packet!";
90 
91  case COMM_RX_TIMEOUT:
92  return "[TxRxResult] There is no status packet!";
93 
94  case COMM_RX_CORRUPT:
95  return "[TxRxResult] Incorrect status packet!";
96 
97  case COMM_NOT_AVAILABLE:
98  return "[TxRxResult] Protocol does not support This function!";
99 
100  default:
101  return "";
102  }
103 }
104 
106 {
107  if (error & ERRBIT_ALERT)
108  return "[RxPacketError] Hardware error occurred. Check the error at Control Table (Hardware Error Status)!";
109 
110  int not_alert_error = error & ~ERRBIT_ALERT;
111 
112  switch(not_alert_error)
113  {
114  case 0:
115  return "";
116 
117  case ERRNUM_RESULT_FAIL:
118  return "[RxPacketError] Failed to process the instruction packet!";
119 
120  case ERRNUM_INSTRUCTION:
121  return "[RxPacketError] Undefined instruction or incorrect instruction!";
122 
123  case ERRNUM_CRC:
124  return "[RxPacketError] CRC doesn't match!";
125 
126  case ERRNUM_DATA_RANGE:
127  return "[RxPacketError] The data value is out of range!";
128 
129  case ERRNUM_DATA_LENGTH:
130  return "[RxPacketError] The data length does not match as expected!";
131 
132  case ERRNUM_DATA_LIMIT:
133  return "[RxPacketError] The data value exceeds the limit value!";
134 
135  case ERRNUM_ACCESS:
136  return "[RxPacketError] Writing or Reading is not available to target address!";
137 
138  default:
139  return "[RxPacketError] Unknown error code!";
140  }
141 }
142 
143 unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size)
144 {
145  uint16_t i;
146  static const uint16_t crc_table[256] = {0x0000,
147  0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011,
148  0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027,
149  0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D,
150  0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A, 0x804B,
151  0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC, 0x80C9,
152  0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5, 0x80FF,
153  0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0, 0x80A5,
154  0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1, 0x8093,
155  0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082,
156  0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197,
157  0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE,
158  0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB,
159  0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC, 0x81D9,
160  0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145, 0x814F,
161  0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173, 0x0176,
162  0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162, 0x8123,
163  0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132,
164  0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104,
165  0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D,
166  0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A, 0x832B,
167  0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F, 0x036A,
168  0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356, 0x035C,
169  0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0, 0x83C5,
170  0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1, 0x83F3,
171  0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2,
172  0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7,
173  0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E,
174  0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A, 0x829B,
175  0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC, 0x82B9,
176  0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6, 0x02EC,
177  0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0, 0x82D5,
178  0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1, 0x8243,
179  0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252,
180  0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264,
181  0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E,
182  0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219, 0x0208,
183  0x820D, 0x8207, 0x0202 };
184 
185  for (uint16_t j = 0; j < data_blk_size; j++)
186  {
187  i = ((uint16_t)(crc_accum >> 8) ^ *data_blk_ptr++) & 0xFF;
188  crc_accum = (crc_accum << 8) ^ crc_table[i];
189  }
190 
191  return crc_accum;
192 }
193 
195 {
196  int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]);
197  int packet_length_out = packet_length_in;
198 
199  if (packet_length_in < 8) // INSTRUCTION, ADDR_L, ADDR_H, CRC16_L, CRC16_H + FF FF FD
200  return;
201 
202  uint8_t *packet_ptr;
203  uint16_t packet_length_before_crc = packet_length_in - 2;
204  for (uint16_t i = 3; i < packet_length_before_crc; i++)
205  {
206  packet_ptr = &packet[i+PKT_INSTRUCTION-2];
207  if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD)
208  packet_length_out++;
209  }
210 
211  if (packet_length_in == packet_length_out) // no stuffing required
212  return;
213 
214  uint16_t out_index = packet_length_out + 6 - 2; // last index before crc
215  uint16_t in_index = packet_length_in + 6 - 2; // last index before crc
216  while (out_index != in_index)
217  {
218  if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF)
219  {
220  packet[out_index--] = 0xFD; // byte stuffing
221  if (out_index != in_index)
222  {
223  packet[out_index--] = packet[in_index--]; // FD
224  packet[out_index--] = packet[in_index--]; // FF
225  packet[out_index--] = packet[in_index--]; // FF
226  }
227  }
228  else
229  {
230  packet[out_index--] = packet[in_index--];
231  }
232  }
233 
234  packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out);
235  packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out);
236 
237  return;
238 }
239 
241 {
242  int i = 0, index = 0;
243  int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]);
244  int packet_length_out = packet_length_in;
245 
246  index = PKT_INSTRUCTION;
247  for (i = 0; i < packet_length_in - 2; i++) // except CRC
248  {
249  if (packet[i+PKT_INSTRUCTION] == 0xFD && packet[i+PKT_INSTRUCTION+1] == 0xFD && packet[i+PKT_INSTRUCTION-1] == 0xFF && packet[i+PKT_INSTRUCTION-2] == 0xFF)
250  { // FF FF FD FD
251  packet_length_out--;
252  i++;
253  }
254  packet[index++] = packet[i+PKT_INSTRUCTION];
255  }
256  packet[index++] = packet[PKT_INSTRUCTION+packet_length_in-2];
257  packet[index++] = packet[PKT_INSTRUCTION+packet_length_in-1];
258 
259  packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out);
260  packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out);
261 }
262 
263 int Protocol2PacketHandler::txPacket(PortHandler *port, uint8_t *txpacket)
264 {
265  uint16_t total_packet_length = 0;
266  uint16_t written_packet_length = 0;
267 
268  if (port->is_using_)
269  return COMM_PORT_BUSY;
270  port->is_using_ = true;
271 
272  // byte stuffing for header
273  addStuffing(txpacket);
274 
275  // check max packet length
276  total_packet_length = DXL_MAKEWORD(txpacket[PKT_LENGTH_L], txpacket[PKT_LENGTH_H]) + 7;
277  // 7: HEADER0 HEADER1 HEADER2 RESERVED ID LENGTH_L LENGTH_H
278  if (total_packet_length > TXPACKET_MAX_LEN)
279  {
280  port->is_using_ = false;
281  return COMM_TX_ERROR;
282  }
283 
284  // make packet header
285  txpacket[PKT_HEADER0] = 0xFF;
286  txpacket[PKT_HEADER1] = 0xFF;
287  txpacket[PKT_HEADER2] = 0xFD;
288  txpacket[PKT_RESERVED] = 0x00;
289 
290  // add CRC16
291  uint16_t crc = updateCRC(0, txpacket, total_packet_length - 2); // 2: CRC16
292  txpacket[total_packet_length - 2] = DXL_LOBYTE(crc);
293  txpacket[total_packet_length - 1] = DXL_HIBYTE(crc);
294 
295  // tx packet
296  port->clearPort();
297  written_packet_length = port->writePort(txpacket, total_packet_length);
298  if (total_packet_length != written_packet_length)
299  {
300  port->is_using_ = false;
301  return COMM_TX_FAIL;
302  }
303 
304  return COMM_SUCCESS;
305 }
306 
307 int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket)
308 {
309  int result = COMM_TX_FAIL;
310 
311  uint16_t rx_length = 0;
312  uint16_t wait_length = 11; // minimum length (HEADER0 HEADER1 HEADER2 RESERVED ID LENGTH_L LENGTH_H INST ERROR CRC16_L CRC16_H)
313 
314  while(true)
315  {
316  rx_length += port->readPort(&rxpacket[rx_length], wait_length - rx_length);
317  if (rx_length >= wait_length)
318  {
319  uint16_t idx = 0;
320 
321  // find packet header
322  for (idx = 0; idx < (rx_length - 3); idx++)
323  {
324  if ((rxpacket[idx] == 0xFF) && (rxpacket[idx+1] == 0xFF) && (rxpacket[idx+2] == 0xFD) && (rxpacket[idx+3] != 0xFD))
325  break;
326  }
327 
328  if (idx == 0) // found at the beginning of the packet
329  {
330  if (rxpacket[PKT_RESERVED] != 0x00 ||
331  rxpacket[PKT_ID] > 0xFC ||
332  DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) > RXPACKET_MAX_LEN ||
333  rxpacket[PKT_INSTRUCTION] != 0x55)
334  {
335  // remove the first byte in the packet
336  for (uint16_t s = 0; s < rx_length - 1; s++)
337  rxpacket[s] = rxpacket[1 + s];
338  //memcpy(&rxpacket[0], &rxpacket[idx], rx_length - idx);
339  rx_length -= 1;
340  continue;
341  }
342 
343  // re-calculate the exact length of the rx packet
344  if (wait_length != DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) + PKT_LENGTH_H + 1)
345  {
346  wait_length = DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) + PKT_LENGTH_H + 1;
347  continue;
348  }
349 
350  if (rx_length < wait_length)
351  {
352  // check timeout
353  if (port->isPacketTimeout() == true)
354  {
355  if (rx_length == 0)
356  {
357  result = COMM_RX_TIMEOUT;
358  }
359  else
360  {
361  result = COMM_RX_CORRUPT;
362  }
363  break;
364  }
365  else
366  {
367  continue;
368  }
369  }
370 
371  // verify CRC16
372  uint16_t crc = DXL_MAKEWORD(rxpacket[wait_length-2], rxpacket[wait_length-1]);
373  if (updateCRC(0, rxpacket, wait_length - 2) == crc)
374  {
375  result = COMM_SUCCESS;
376  }
377  else
378  {
379  result = COMM_RX_CORRUPT;
380  }
381  break;
382  }
383  else
384  {
385  // remove unnecessary packets
386  for (uint16_t s = 0; s < rx_length - idx; s++)
387  rxpacket[s] = rxpacket[idx + s];
388  //memcpy(&rxpacket[0], &rxpacket[idx], rx_length - idx);
389  rx_length -= idx;
390  }
391  }
392  else
393  {
394  // check timeout
395  if (port->isPacketTimeout() == true)
396  {
397  if (rx_length == 0)
398  {
399  result = COMM_RX_TIMEOUT;
400  }
401  else
402  {
403  result = COMM_RX_CORRUPT;
404  }
405  break;
406  }
407  }
408 #if defined(__linux__) || defined(__APPLE__)
409  usleep(0);
410 #elif defined(_WIN32) || defined(_WIN64)
411  Sleep(0);
412 #endif
413  }
414  port->is_using_ = false;
415 
416  if (result == COMM_SUCCESS)
417  removeStuffing(rxpacket);
418 
419  return result;
420 }
421 
422 // NOT for BulkRead / SyncRead instruction
423 int Protocol2PacketHandler::txRxPacket(PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error)
424 {
425  int result = COMM_TX_FAIL;
426 
427  // tx packet
428  result = txPacket(port, txpacket);
429  if (result != COMM_SUCCESS)
430  return result;
431 
432  // (Instruction == BulkRead or SyncRead) == this function is not available.
433  if (txpacket[PKT_INSTRUCTION] == INST_BULK_READ || txpacket[PKT_INSTRUCTION] == INST_SYNC_READ)
434  result = COMM_NOT_AVAILABLE;
435 
436  // (ID == Broadcast ID) == no need to wait for status packet or not available.
437  // (Instruction == action) == no need to wait for status packet
438  if (txpacket[PKT_ID] == BROADCAST_ID || txpacket[PKT_INSTRUCTION] == INST_ACTION)
439  {
440  port->is_using_ = false;
441  return result;
442  }
443 
444  // set packet timeout
445  if (txpacket[PKT_INSTRUCTION] == INST_READ)
446  {
447  port->setPacketTimeout((uint16_t)(DXL_MAKEWORD(txpacket[PKT_PARAMETER0+2], txpacket[PKT_PARAMETER0+3]) + 11));
448  }
449  else
450  {
451  port->setPacketTimeout((uint16_t)11);
452  // HEADER0 HEADER1 HEADER2 RESERVED ID LENGTH_L LENGTH_H INST ERROR CRC16_L CRC16_H
453  }
454 
455  // rx packet
456  do {
457  result = rxPacket(port, rxpacket);
458  } while (result == COMM_SUCCESS && txpacket[PKT_ID] != rxpacket[PKT_ID]);
459 
460  if (result == COMM_SUCCESS && txpacket[PKT_ID] == rxpacket[PKT_ID])
461  {
462  if (error != 0)
463  *error = (uint8_t)rxpacket[PKT_ERROR];
464  }
465 
466  return result;
467 }
468 
469 int Protocol2PacketHandler::ping(PortHandler *port, uint8_t id, uint8_t *error)
470 {
471  return ping(port, id, 0, error);
472 }
473 
474 int Protocol2PacketHandler::ping(PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error)
475 {
476  int result = COMM_TX_FAIL;
477 
478  uint8_t txpacket[10] = {0};
479  uint8_t rxpacket[14] = {0};
480 
481  if (id >= BROADCAST_ID)
482  return COMM_NOT_AVAILABLE;
483 
484  txpacket[PKT_ID] = id;
485  txpacket[PKT_LENGTH_L] = 3;
486  txpacket[PKT_LENGTH_H] = 0;
487  txpacket[PKT_INSTRUCTION] = INST_PING;
488 
489  result = txRxPacket(port, txpacket, rxpacket, error);
490  if (result == COMM_SUCCESS && model_number != 0)
491  *model_number = DXL_MAKEWORD(rxpacket[PKT_PARAMETER0+1], rxpacket[PKT_PARAMETER0+2]);
492 
493  return result;
494 }
495 
496 int Protocol2PacketHandler::broadcastPing(PortHandler *port, std::vector<uint8_t> &id_list)
497 {
498  const int STATUS_LENGTH = 14;
499  int result = COMM_TX_FAIL;
500 
501  id_list.clear();
502 
503  uint16_t rx_length = 0;
504  uint16_t wait_length = STATUS_LENGTH * MAX_ID;
505 
506  uint8_t txpacket[10] = {0};
507  uint8_t rxpacket[STATUS_LENGTH * MAX_ID] = {0};
508 
509  double tx_time_per_byte = (1000.0 / (double)port->getBaudRate()) * 10.0;
510 
511  txpacket[PKT_ID] = BROADCAST_ID;
512  txpacket[PKT_LENGTH_L] = 3;
513  txpacket[PKT_LENGTH_H] = 0;
514  txpacket[PKT_INSTRUCTION] = INST_PING;
515 
516  result = txPacket(port, txpacket);
517  if (result != COMM_SUCCESS)
518  {
519  port->is_using_ = false;
520  return result;
521  }
522 
523  // set rx timeout
524  //port->setPacketTimeout((uint16_t)(wait_length * 30));
525  port->setPacketTimeout(((double)wait_length * tx_time_per_byte) + (3.0 * (double)MAX_ID) + 16.0);
526 
527  while(1)
528  {
529  rx_length += port->readPort(&rxpacket[rx_length], wait_length - rx_length);
530  if (port->isPacketTimeout() == true)// || rx_length >= wait_length)
531  break;
532  }
533 
534  port->is_using_ = false;
535 
536  if (rx_length == 0)
537  return COMM_RX_TIMEOUT;
538 
539  while(1)
540  {
541  if (rx_length < STATUS_LENGTH)
542  return COMM_RX_CORRUPT;
543 
544  uint16_t idx = 0;
545 
546  // find packet header
547  for (idx = 0; idx < (rx_length - 2); idx++)
548  {
549  if (rxpacket[idx] == 0xFF && rxpacket[idx+1] == 0xFF && rxpacket[idx+2] == 0xFD)
550  break;
551  }
552 
553  if (idx == 0) // found at the beginning of the packet
554  {
555  // verify CRC16
556  uint16_t crc = DXL_MAKEWORD(rxpacket[STATUS_LENGTH-2], rxpacket[STATUS_LENGTH-1]);
557 
558  if (updateCRC(0, rxpacket, STATUS_LENGTH - 2) == crc)
559  {
560  result = COMM_SUCCESS;
561 
562  id_list.push_back(rxpacket[PKT_ID]);
563 
564  for (uint16_t s = 0; s < rx_length - STATUS_LENGTH; s++)
565  rxpacket[s] = rxpacket[STATUS_LENGTH + s];
566  rx_length -= STATUS_LENGTH;
567 
568  if (rx_length == 0)
569  return result;
570  }
571  else
572  {
573  result = COMM_RX_CORRUPT;
574 
575  // remove header (0xFF 0xFF 0xFD)
576  for (uint16_t s = 0; s < rx_length - 3; s++)
577  rxpacket[s] = rxpacket[3 + s];
578  rx_length -= 3;
579  }
580  }
581  else
582  {
583  // remove unnecessary packets
584  for (uint16_t s = 0; s < rx_length - idx; s++)
585  rxpacket[s] = rxpacket[idx + s];
586  rx_length -= idx;
587  }
588  }
589 
590  return result;
591 }
592 
594 {
595  uint8_t txpacket[10] = {0};
596 
597  txpacket[PKT_ID] = id;
598  txpacket[PKT_LENGTH_L] = 3;
599  txpacket[PKT_LENGTH_H] = 0;
600  txpacket[PKT_INSTRUCTION] = INST_ACTION;
601 
602  return txRxPacket(port, txpacket, 0);
603 }
604 
605 int Protocol2PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error)
606 {
607  uint8_t txpacket[10] = {0};
608  uint8_t rxpacket[11] = {0};
609 
610  txpacket[PKT_ID] = id;
611  txpacket[PKT_LENGTH_L] = 3;
612  txpacket[PKT_LENGTH_H] = 0;
613  txpacket[PKT_INSTRUCTION] = INST_REBOOT;
614 
615  return txRxPacket(port, txpacket, rxpacket, error);
616 }
617 
618 int Protocol2PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error)
619 {
620  uint8_t txpacket[15] = {0};
621  uint8_t rxpacket[11] = {0};
622 
623  txpacket[PKT_ID] = id;
624  txpacket[PKT_LENGTH_L] = 8;
625  txpacket[PKT_LENGTH_H] = 0;
626  txpacket[PKT_INSTRUCTION] = INST_CLEAR;
627  txpacket[PKT_PARAMETER0] = 0x01;
628  txpacket[PKT_PARAMETER0+1] = 0x44;
629  txpacket[PKT_PARAMETER0+2] = 0x58;
630  txpacket[PKT_PARAMETER0+3] = 0x4C;
631  txpacket[PKT_PARAMETER0+4] = 0x22;
632 
633  return txRxPacket(port, txpacket, rxpacket, error);
634 }
635 
636 int Protocol2PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error)
637 {
638  uint8_t txpacket[11] = {0};
639  uint8_t rxpacket[11] = {0};
640 
641  txpacket[PKT_ID] = id;
642  txpacket[PKT_LENGTH_L] = 4;
643  txpacket[PKT_LENGTH_H] = 0;
645  txpacket[PKT_PARAMETER0] = option;
646 
647  return txRxPacket(port, txpacket, rxpacket, error);
648 }
649 
650 int Protocol2PacketHandler::readTx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length)
651 {
652  int result = COMM_TX_FAIL;
653 
654  uint8_t txpacket[14] = {0};
655 
656  if (id >= BROADCAST_ID)
657  return COMM_NOT_AVAILABLE;
658 
659  txpacket[PKT_ID] = id;
660  txpacket[PKT_LENGTH_L] = 7;
661  txpacket[PKT_LENGTH_H] = 0;
662  txpacket[PKT_INSTRUCTION] = INST_READ;
663  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
664  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
665  txpacket[PKT_PARAMETER0+2] = (uint8_t)DXL_LOBYTE(length);
666  txpacket[PKT_PARAMETER0+3] = (uint8_t)DXL_HIBYTE(length);
667 
668  result = txPacket(port, txpacket);
669 
670  // set packet timeout
671  if (result == COMM_SUCCESS)
672  port->setPacketTimeout((uint16_t)(length + 11));
673 
674  return result;
675 }
676 
677 int Protocol2PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error)
678 {
679  int result = COMM_TX_FAIL;
680  uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);
681  //(length + 11 + (length/3)); // (length/3): consider stuffing
682 
683  if (rxpacket == NULL)
684  return result;
685 
686  do {
687  result = rxPacket(port, rxpacket);
688  } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id);
689 
690  if (result == COMM_SUCCESS && rxpacket[PKT_ID] == id)
691  {
692  if (error != 0)
693  *error = (uint8_t)rxpacket[PKT_ERROR];
694 
695  for (uint16_t s = 0; s < length; s++)
696  {
697  data[s] = rxpacket[PKT_PARAMETER0 + 1 + s];
698  }
699  //memcpy(data, &rxpacket[PKT_PARAMETER0+1], length);
700  }
701 
702  free(rxpacket);
703  //delete[] rxpacket;
704  return result;
705 }
706 
707 int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
708 {
709  int result = COMM_TX_FAIL;
710 
711  uint8_t txpacket[14] = {0};
712  uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);
713  //(length + 11 + (length/3)); // (length/3): consider stuffing
714 
715  if (rxpacket == NULL)
716  return result;
717 
718  if (id >= BROADCAST_ID)
719  {
720  free(rxpacket);
721  return COMM_NOT_AVAILABLE;
722  }
723 
724  txpacket[PKT_ID] = id;
725  txpacket[PKT_LENGTH_L] = 7;
726  txpacket[PKT_LENGTH_H] = 0;
727  txpacket[PKT_INSTRUCTION] = INST_READ;
728  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
729  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
730  txpacket[PKT_PARAMETER0+2] = (uint8_t)DXL_LOBYTE(length);
731  txpacket[PKT_PARAMETER0+3] = (uint8_t)DXL_HIBYTE(length);
732 
733  result = txRxPacket(port, txpacket, rxpacket, error);
734  if (result == COMM_SUCCESS)
735  {
736  if (error != 0)
737  *error = (uint8_t)rxpacket[PKT_ERROR];
738 
739  for (uint16_t s = 0; s < length; s++)
740  {
741  data[s] = rxpacket[PKT_PARAMETER0 + 1 + s];
742  }
743  //memcpy(data, &rxpacket[PKT_PARAMETER0+1], length);
744  }
745 
746  free(rxpacket);
747  //delete[] rxpacket;
748  return result;
749 }
750 
751 int Protocol2PacketHandler::read1ByteTx(PortHandler *port, uint8_t id, uint16_t address)
752 {
753  return readTx(port, id, address, 1);
754 }
755 int Protocol2PacketHandler::read1ByteRx(PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error)
756 {
757  uint8_t data_read[1] = {0};
758  int result = readRx(port, id, 1, data_read, error);
759  if (result == COMM_SUCCESS)
760  *data = data_read[0];
761  return result;
762 }
763 int Protocol2PacketHandler::read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error)
764 {
765  uint8_t data_read[1] = {0};
766  int result = readTxRx(port, id, address, 1, data_read, error);
767  if (result == COMM_SUCCESS)
768  *data = data_read[0];
769  return result;
770 }
771 
772 int Protocol2PacketHandler::read2ByteTx(PortHandler *port, uint8_t id, uint16_t address)
773 {
774  return readTx(port, id, address, 2);
775 }
776 int Protocol2PacketHandler::read2ByteRx(PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error)
777 {
778  uint8_t data_read[2] = {0};
779  int result = readRx(port, id, 2, data_read, error);
780  if (result == COMM_SUCCESS)
781  *data = DXL_MAKEWORD(data_read[0], data_read[1]);
782  return result;
783 }
784 int Protocol2PacketHandler::read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error)
785 {
786  uint8_t data_read[2] = {0};
787  int result = readTxRx(port, id, address, 2, data_read, error);
788  if (result == COMM_SUCCESS)
789  *data = DXL_MAKEWORD(data_read[0], data_read[1]);
790  return result;
791 }
792 
793 int Protocol2PacketHandler::read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)
794 {
795  return readTx(port, id, address, 4);
796 }
797 int Protocol2PacketHandler::read4ByteRx(PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error)
798 {
799  uint8_t data_read[4] = {0};
800  int result = readRx(port, id, 4, data_read, error);
801  if (result == COMM_SUCCESS)
802  *data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
803  return result;
804 }
805 int Protocol2PacketHandler::read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error)
806 {
807  uint8_t data_read[4] = {0};
808  int result = readTxRx(port, id, address, 4, data_read, error);
809  if (result == COMM_SUCCESS)
810  *data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
811  return result;
812 }
813 
814 
815 int Protocol2PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
816 {
817  int result = COMM_TX_FAIL;
818 
819  uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
820 
821  if (txpacket == NULL)
822  return result;
823 
824  txpacket[PKT_ID] = id;
825  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5);
826  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5);
827  txpacket[PKT_INSTRUCTION] = INST_WRITE;
828  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
829  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
830 
831  for (uint16_t s = 0; s < length; s++)
832  txpacket[PKT_PARAMETER0+2+s] = data[s];
833  //memcpy(&txpacket[PKT_PARAMETER0+2], data, length);
834 
835  result = txPacket(port, txpacket);
836  port->is_using_ = false;
837 
838  free(txpacket);
839  //delete[] txpacket;
840  return result;
841 }
842 
843 int Protocol2PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
844 {
845  int result = COMM_TX_FAIL;
846 
847  uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
848  uint8_t rxpacket[11] = {0};
849 
850  if (txpacket == NULL)
851  return result;
852 
853  txpacket[PKT_ID] = id;
854  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5);
855  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5);
856  txpacket[PKT_INSTRUCTION] = INST_WRITE;
857  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
858  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
859 
860  for (uint16_t s = 0; s < length; s++)
861  txpacket[PKT_PARAMETER0+2+s] = data[s];
862  //memcpy(&txpacket[PKT_PARAMETER0+2], data, length);
863 
864  result = txRxPacket(port, txpacket, rxpacket, error);
865 
866  free(txpacket);
867  //delete[] txpacket;
868  return result;
869 }
870 
871 int Protocol2PacketHandler::write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data)
872 {
873  uint8_t data_write[1] = { data };
874  return writeTxOnly(port, id, address, 1, data_write);
875 }
876 int Protocol2PacketHandler::write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error)
877 {
878  uint8_t data_write[1] = { data };
879  return writeTxRx(port, id, address, 1, data_write, error);
880 }
881 
882 int Protocol2PacketHandler::write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data)
883 {
884  uint8_t data_write[2] = { DXL_LOBYTE(data), DXL_HIBYTE(data) };
885  return writeTxOnly(port, id, address, 2, data_write);
886 }
887 int Protocol2PacketHandler::write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error)
888 {
889  uint8_t data_write[2] = { DXL_LOBYTE(data), DXL_HIBYTE(data) };
890  return writeTxRx(port, id, address, 2, data_write, error);
891 }
892 
893 int Protocol2PacketHandler::write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)
894 {
895  uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
896  return writeTxOnly(port, id, address, 4, data_write);
897 }
898 int Protocol2PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error)
899 {
900  uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
901  return writeTxRx(port, id, address, 4, data_write, error);
902 }
903 
904 int Protocol2PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
905 {
906  int result = COMM_TX_FAIL;
907 
908  uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
909 
910  if (txpacket == NULL)
911  return result;
912 
913  txpacket[PKT_ID] = id;
914  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5);
915  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5);
916  txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
917  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
918  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
919 
920  for (uint16_t s = 0; s < length; s++)
921  txpacket[PKT_PARAMETER0+2+s] = data[s];
922  //memcpy(&txpacket[PKT_PARAMETER0+2], data, length);
923 
924  result = txPacket(port, txpacket);
925  port->is_using_ = false;
926 
927  free(txpacket);
928  //delete[] txpacket;
929  return result;
930 }
931 
932 int Protocol2PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
933 {
934  int result = COMM_TX_FAIL;
935 
936  uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
937  uint8_t rxpacket[11] = {0};
938 
939  if (txpacket == NULL)
940  return result;
941 
942  txpacket[PKT_ID] = id;
943  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5);
944  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5);
945  txpacket[PKT_INSTRUCTION] = INST_REG_WRITE;
946  txpacket[PKT_PARAMETER0+0] = (uint8_t)DXL_LOBYTE(address);
947  txpacket[PKT_PARAMETER0+1] = (uint8_t)DXL_HIBYTE(address);
948 
949  for (uint16_t s = 0; s < length; s++)
950  txpacket[PKT_PARAMETER0+2+s] = data[s];
951  //memcpy(&txpacket[PKT_PARAMETER0+2], data, length);
952 
953  result = txRxPacket(port, txpacket, rxpacket, error);
954 
955  free(txpacket);
956  //delete[] txpacket;
957  return result;
958 }
959 
960 int Protocol2PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
961 {
962  int result = COMM_TX_FAIL;
963 
964  uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3));
965  // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
966 
967  if (txpacket == NULL)
968  return result;
969 
970  txpacket[PKT_ID] = BROADCAST_ID;
971  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
972  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
973  txpacket[PKT_INSTRUCTION] = INST_SYNC_READ;
974  txpacket[PKT_PARAMETER0+0] = DXL_LOBYTE(start_address);
975  txpacket[PKT_PARAMETER0+1] = DXL_HIBYTE(start_address);
976  txpacket[PKT_PARAMETER0+2] = DXL_LOBYTE(data_length);
977  txpacket[PKT_PARAMETER0+3] = DXL_HIBYTE(data_length);
978 
979  for (uint16_t s = 0; s < param_length; s++)
980  txpacket[PKT_PARAMETER0+4+s] = param[s];
981  //memcpy(&txpacket[PKT_PARAMETER0+4], param, param_length);
982 
983  result = txPacket(port, txpacket);
984  if (result == COMM_SUCCESS)
985  port->setPacketTimeout((uint16_t)((11 + data_length) * param_length));
986 
987  free(txpacket);
988  return result;
989 }
990 
991 int Protocol2PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
992 {
993  int result = COMM_TX_FAIL;
994 
995  uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3));
996  // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
997 
998  if (txpacket == NULL)
999  return result;
1000 
1001  txpacket[PKT_ID] = BROADCAST_ID;
1002  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
1003  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H
1004  txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE;
1005  txpacket[PKT_PARAMETER0+0] = DXL_LOBYTE(start_address);
1006  txpacket[PKT_PARAMETER0+1] = DXL_HIBYTE(start_address);
1007  txpacket[PKT_PARAMETER0+2] = DXL_LOBYTE(data_length);
1008  txpacket[PKT_PARAMETER0+3] = DXL_HIBYTE(data_length);
1009 
1010  for (uint16_t s = 0; s < param_length; s++)
1011  txpacket[PKT_PARAMETER0+4+s] = param[s];
1012  //memcpy(&txpacket[PKT_PARAMETER0+4], param, param_length);
1013 
1014  result = txRxPacket(port, txpacket, 0, 0);
1015 
1016  free(txpacket);
1017  //delete[] txpacket;
1018  return result;
1019 }
1020 
1021 int Protocol2PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length)
1022 {
1023  int result = COMM_TX_FAIL;
1024 
1025  uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3));
1026  // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H
1027 
1028  if (txpacket == NULL)
1029  return result;
1030 
1031  txpacket[PKT_ID] = BROADCAST_ID;
1032  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H
1033  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H
1034  txpacket[PKT_INSTRUCTION] = INST_BULK_READ;
1035 
1036  for (uint16_t s = 0; s < param_length; s++)
1037  txpacket[PKT_PARAMETER0+s] = param[s];
1038  //memcpy(&txpacket[PKT_PARAMETER0], param, param_length);
1039 
1040  result = txPacket(port, txpacket);
1041  if (result == COMM_SUCCESS)
1042  {
1043  int wait_length = 0;
1044  for (uint16_t i = 0; i < param_length; i += 5)
1045  wait_length += DXL_MAKEWORD(param[i+3], param[i+4]) + 10;
1046  port->setPacketTimeout((uint16_t)wait_length);
1047  }
1048 
1049  free(txpacket);
1050  //delete[] txpacket;
1051  return result;
1052 }
1053 
1054 int Protocol2PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length)
1055 {
1056  int result = COMM_TX_FAIL;
1057 
1058  uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3));
1059  // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H
1060 
1061  if (txpacket == NULL)
1062  return result;
1063 
1064  txpacket[PKT_ID] = BROADCAST_ID;
1065  txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H
1066  txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H
1067  txpacket[PKT_INSTRUCTION] = INST_BULK_WRITE;
1068 
1069  for (uint16_t s = 0; s < param_length; s++)
1070  txpacket[PKT_PARAMETER0+s] = param[s];
1071  //memcpy(&txpacket[PKT_PARAMETER0], param, param_length);
1072 
1073  result = txRxPacket(port, txpacket, 0, 0);
1074 
1075  free(txpacket);
1076  //delete[] txpacket;
1077  return result;
1078 }
#define COMM_RX_FAIL
#define DXL_MAKEDWORD(a, b)
#define TXPACKET_MAX_LEN
int readTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
The function that transmits INST_READ instruction packet, and read data from received packet The fun...
static Protocol2PacketHandler * unique_instance_
int read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)
The function that calls Protocol2PacketHandler::readTx() function for reading 4 byte data The functi...
int clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error=0)
The function that reset multi-turn revolution information of Dynamixel The function makes an instruc...
virtual void clearPort()=0
The function that clears the port The function clears the port.
#define ERRNUM_INSTRUCTION
int bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length)
The function that transmits INST_BULK_WRITE instruction packet The function makes an instruction pac...
#define PKT_ID
#define INST_READ
#define INST_REBOOT
#define COMM_SUCCESS
int ping(PortHandler *port, uint8_t id, uint8_t *error=0)
The function that pings Dynamixel but doesn&#39;t take its model number The function calls Protocol2Pack...
#define PKT_LENGTH_H
#define PKT_LENGTH_L
int read4ByteRx(PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readRx() function and reads 4 byte data on the packet...
uint16_t updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size)
int regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynami...
int regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynami...
#define DXL_MAKEWORD(a, b)
#define RXPACKET_MAX_LEN
int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data)
The function that calls Protocol2PacketHandler::writeTxOnly() for writing 2 byte data The function c...
XmlRpcServer s
int syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
The function that transmits INST_SYNC_WRITE instruction packet The function makes an instruction pac...
#define ERRNUM_ACCESS
int factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error=0)
The function that makes Dynamixel reset as it was produced in the factory The function makes an inst...
int writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
The function that transmits INST_WRITE instruction packet with the data for write The function makes...
const char * getTxRxResult(int result)
The function that gets description of communication result.
#define PKT_HEADER2
#define PKT_INSTRUCTION
int write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::writeTxRx() for writing 4 byte data and receives the ...
#define COMM_RX_TIMEOUT
#define COMM_TX_FAIL
#define PKT_PARAMETER0
#define ERRNUM_CRC
#define PKT_ERROR
int rxPacket(PortHandler *port, uint8_t *rxpacket)
The function that receives packet (rxpacket) during designated time via PortHandler port The functio...
#define ERRNUM_DATA_LIMIT
int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)
The function that calls Protocol2PacketHandler::writeTxOnly() for writing 4 byte data The function c...
int read2ByteRx(PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readRx() function and reads 2 byte data on the packet...
#define COMM_RX_WAITING
int read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readTxRx() function for reading 2 byte data The func...
#define INST_CLEAR
#define DXL_LOBYTE(w)
#define ERRNUM_DATA_RANGE
#define INST_FACTORY_RESET
#define INST_WRITE
int txPacket(PortHandler *port, uint8_t *txpacket)
The function that transmits the instruction packet txpacket via PortHandler port. The function clear...
int syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
The function that transmits INST_SYNC_READ instruction packet The function makes an instruction pack...
int write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::writeTxRx() for writing 2 byte data and receives the ...
int read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readTxRx() function for reading 1 byte data The func...
int read2ByteTx(PortHandler *port, uint8_t id, uint16_t address)
The function that calls Protocol2PacketHandler::readTx() function for reading 2 byte data The functi...
#define INST_BULK_READ
int reboot(PortHandler *port, uint8_t id, uint8_t *error=0)
The function that makes Dynamixel reboot The function makes an instruction packet with INST_REBOOT...
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56
#define INST_REG_WRITE
int read1ByteRx(PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readRx() function and reads 1 byte data on the packet...
#define COMM_TX_ERROR
#define INST_SYNC_WRITE
#define ERRNUM_DATA_LENGTH
int readTx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length)
The function that transmits INST_READ instruction packet The function makes an instruction packet wi...
#define PKT_HEADER1
int read1ByteTx(PortHandler *port, uint8_t id, uint16_t address)
The function that calls Protocol2PacketHandler::readTx() function for reading 1 byte data The functi...
virtual int writePort(uint8_t *packet, int length)=0
The function that writes bytes on the port buffer The function writes bytes on the port buffer...
int writeTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
The function that transmits INST_WRITE instruction packet with the data for write, and receives the packet The function makes an instruction packet with INST_WRITE and the data for write, transmits and receives the packet with Protocol2PacketHandler::txRxPacket(), gets the error from the packet.
#define DXL_HIWORD(l)
int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::writeTxRx() for writing 1 byte data and receives the ...
#define INST_PING
virtual bool isPacketTimeout()=0
The function that checks whether packet timeout is occurred The function checks whether current time...
#define DXL_HIBYTE(w)
int broadcastPing(PortHandler *port, std::vector< uint8_t > &id_list)
(Available only in Protocol 2.0) The function that pings all connected Dynamixel
#define MAX_ID
int readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error=0)
The function that receives the packet and reads the data in the packet The function receives the pac...
The class for control Dynamixel by using Protocol2.0.
#define COMM_RX_CORRUPT
int bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length)
The function that transmits INST_BULK_READ instruction packet The function makes an instruction pack...
#define PKT_RESERVED
#define PKT_HEADER0
virtual int readPort(uint8_t *packet, int length)=0
The function that reads bytes from the port buffer The function gets bytes from the port buffer...
#define INST_BULK_WRITE
#define COMM_NOT_AVAILABLE
int action(PortHandler *port, uint8_t id)
The function that makes Dynamixels run as written in the Dynamixel register The function makes an in...
int txRxPacket(PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error=0)
The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time v...
const char * getRxPacketError(uint8_t error)
The function that gets description of hardware error.
virtual int getBaudRate()=0
The function that returns current baudrate set into the port handler The function returns current ba...
#define COMM_PORT_BUSY
int read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)
The function that calls Protocol2PacketHandler::readTxRx() function for reading 4 byte data The func...
bool is_using_
shows whether the port is in use
Definition: port_handler.h:67
#define ERRNUM_RESULT_FAIL
#define INST_ACTION
virtual void setPacketTimeout(uint16_t packet_length)=0
The function that sets and starts stopwatch for watching packet timeout The function sets the stopwa...
#define ERRBIT_ALERT
#define DXL_LOWORD(l)
#define INST_SYNC_READ
#define BROADCAST_ID
int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data)
The function that calls Protocol2PacketHandler::writeTxOnly() for writing 1 byte data The function c...


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55