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