19 #if defined(__linux__)
21 #elif defined(__APPLE__)
23 #elif defined(_WIN32) || defined(_WIN64)
26 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
27 #include "../../include/dynamixel_sdk/protocol1_packet_handler.h"
33 #define TXPACKET_MAX_LEN (250)
34 #define RXPACKET_MAX_LEN (250)
41 #define PKT_INSTRUCTION 4
43 #define PKT_PARAMETER0 5
46 #define ERRBIT_VOLTAGE 1 // Supplied voltage is out of the range (operating volatage set in the control table)
47 #define ERRBIT_ANGLE 2 // Goal position is written out of the range (from CW angle limit to CCW angle limit)
48 #define ERRBIT_OVERHEAT 4 // Temperature is out of the range (operating temperature set in the control table)
49 #define ERRBIT_RANGE 8 // Command(setting value) is out of the range for use.
50 #define ERRBIT_CHECKSUM 16 // Instruction packet checksum is incorrect.
51 #define ERRBIT_OVERLOAD 32 // The current load cannot be controlled by the set torque.
52 #define ERRBIT_INSTRUCTION 64 // Undefined instruction or delivering the action command without the reg_write command.
65 return "[TxRxResult] Communication success.";
68 return "[TxRxResult] Port is in use!";
71 return "[TxRxResult] Failed transmit instruction packet!";
74 return "[TxRxResult] Failed get status packet from device!";
77 return "[TxRxResult] Incorrect instruction packet!";
80 return "[TxRxResult] Now recieving status packet!";
83 return "[TxRxResult] There is no status packet!";
86 return "[TxRxResult] Incorrect status packet!";
89 return "[TxRxResult] Protocol does not support This function!";
99 return "[RxPacketError] Input voltage error!";
102 return "[RxPacketError] Angle limit error!";
105 return "[RxPacketError] Overheat error!";
108 return "[RxPacketError] Out of range error!";
111 return "[RxPacketError] Checksum error!";
114 return "[RxPacketError] Overload error!";
117 return "[RxPacketError] Instruction code error!";
124 uint8_t checksum = 0;
125 uint8_t total_packet_length = txpacket[
PKT_LENGTH] + 4;
126 uint8_t written_packet_length = 0;
144 for (uint16_t idx = 2; idx < total_packet_length - 1; idx++)
145 checksum += txpacket[idx];
146 txpacket[total_packet_length - 1] = ~checksum;
150 written_packet_length = port->
writePort(txpacket, total_packet_length);
151 if (total_packet_length != written_packet_length)
164 uint8_t checksum = 0;
165 uint8_t rx_length = 0;
166 uint8_t wait_length = 6;
170 rx_length += port->
readPort(&rxpacket[rx_length], wait_length - rx_length);
171 if (rx_length >= wait_length)
176 for (idx = 0; idx < (rx_length - 1); idx++)
178 if (rxpacket[idx] == 0xFF && rxpacket[idx+1] == 0xFF)
184 if (rxpacket[
PKT_ID] > 0xFD ||
189 for (uint16_t
s = 0;
s < rx_length - 1;
s++)
190 rxpacket[
s] = rxpacket[1 +
s];
203 if (rx_length < wait_length)
225 for (uint16_t i = 2; i < wait_length - 1; i++)
226 checksum += rxpacket[i];
227 checksum = ~checksum;
230 if (rxpacket[wait_length - 1] == checksum)
243 for (uint16_t
s = 0;
s < rx_length - idx;
s++)
244 rxpacket[
s] = rxpacket[idx +
s];
319 return ping(port,
id, 0, error);
326 uint8_t txpacket[6] = {0};
327 uint8_t rxpacket[6] = {0};
336 result =
txRxPacket(port, txpacket, rxpacket, error);
339 uint8_t data_read[2] = {0};
340 result =
readTxRx(port,
id, 0, 2, data_read);
354 uint8_t txpacket[6] = {0};
375 uint8_t txpacket[6] = {0};
376 uint8_t rxpacket[6] = {0};
382 return txRxPacket(port, txpacket, rxpacket, error);
389 uint8_t txpacket[8] = {0};
415 if (rxpacket == NULL)
428 for (uint16_t
s = 0;
s < length;
s++)
444 uint8_t txpacket[8] = {0};
447 if (rxpacket == NULL)
462 result =
txRxPacket(port, txpacket, rxpacket, error);
469 for (uint16_t
s = 0;
s < length;
s++)
483 return readTx(port,
id, address, 1);
487 uint8_t data_read[1] = {0};
488 int result =
readRx(port,
id, 1, data_read, error);
490 *data = data_read[0];
495 uint8_t data_read[1] = {0};
496 int result =
readTxRx(port,
id, address, 1, data_read, error);
498 *data = data_read[0];
504 return readTx(port,
id, address, 2);
508 uint8_t data_read[2] = {0};
509 int result =
readRx(port,
id, 2, data_read, error);
516 uint8_t data_read[2] = {0};
517 int result =
readTxRx(port,
id, address, 2, data_read, error);
525 return readTx(port,
id, address, 4);
529 uint8_t data_read[4] = {0};
530 int result =
readRx(port,
id, 4, data_read, error);
537 uint8_t data_read[4] = {0};
538 int result =
readTxRx(port,
id, address, 4, data_read, error);
548 uint8_t *txpacket = (uint8_t *)malloc(length+7);
551 if (txpacket == NULL)
559 for (uint16_t
s = 0;
s < length;
s++)
575 uint8_t *txpacket = (uint8_t *)malloc(length+7);
577 uint8_t rxpacket[6] = {0};
579 if (txpacket == NULL)
587 for (uint16_t
s = 0;
s < length;
s++)
591 result =
txRxPacket(port, txpacket, rxpacket, error);
600 uint8_t data_write[1] = { data };
601 return writeTxOnly(port,
id, address, 1, data_write);
605 uint8_t data_write[1] = { data };
606 return writeTxRx(port,
id, address, 1, data_write, error);
612 return writeTxOnly(port,
id, address, 2, data_write);
617 return writeTxRx(port,
id, address, 2, data_write, error);
623 return writeTxOnly(port,
id, address, 4, data_write);
628 return writeTxRx(port,
id, address, 4, data_write, error);
635 uint8_t *txpacket = (uint8_t *)malloc(length+6);
638 if (txpacket == NULL)
646 for (uint16_t
s = 0;
s < length;
s++)
662 uint8_t *txpacket = (uint8_t *)malloc(length+6);
664 uint8_t rxpacket[6] = {0};
666 if (txpacket == NULL)
674 for (uint16_t
s = 0;
s < length;
s++)
678 result =
txRxPacket(port, txpacket, rxpacket, error);
694 uint8_t *txpacket = (uint8_t *)malloc(param_length+8);
698 if (txpacket == NULL)
707 for (uint16_t
s = 0;
s < param_length;
s++)
722 uint8_t *txpacket = (uint8_t *)malloc(param_length+7);
726 if (txpacket == NULL)
734 for (uint16_t
s = 0;
s < param_length;
s++)
742 for (uint16_t i = 0; i < param_length; i += 3)
743 wait_length +=
param[i] + 7;