25 #if defined(__linux__)
28 #elif defined(__APPLE__)
31 #elif defined(_WIN32) || defined(_WIN64)
35 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
36 #include "../../include/mercury_sdk/protocol2_packet_handler.h"
42 #define TXPACKET_MAX_LEN (1*1024)
43 #define RXPACKET_MAX_LEN (1*1024)
49 #define PKT_RESERVED 3
51 #define PKT_LENGTH_L 5
52 #define PKT_LENGTH_H 6
53 #define PKT_INSTRUCTION 7
55 #define PKT_PARAMETER0 8
58 #define ERRNUM_RESULT_FAIL 1
59 #define ERRNUM_INSTRUCTION 2
61 #define ERRNUM_DATA_RANGE 4
62 #define ERRNUM_DATA_LENGTH 5
63 #define ERRNUM_DATA_LIMIT 6
64 #define ERRNUM_ACCESS 7
66 #define ERRBIT_ALERT 128
72 Protocol2PacketHandler::Protocol2PacketHandler() { }
79 return "[TxRxResult] Communication success.";
82 return "[TxRxResult] Port is in use!";
85 return "[TxRxResult] Failed transmit instruction packet!";
88 return "[TxRxResult] Failed get status packet from device!";
91 return "[TxRxResult] Incorrect instruction packet!";
94 return "[TxRxResult] Now recieving status packet!";
97 return "[TxRxResult] There is no status packet!";
100 return "[TxRxResult] Incorrect status packet!";
103 return "[TxRxResult] Protocol does not support This function!";
113 return "[RxPacketError] Hardware error occurred. Check the error at Control Table (Hardware Error Status)!";
117 switch(not_alert_error)
123 return "[RxPacketError] Failed to process the instruction packet!";
126 return "[RxPacketError] Undefined instruction or incorrect instruction!";
129 return "[RxPacketError] CRC doesn't match!";
132 return "[RxPacketError] The data value is out of range!";
135 return "[RxPacketError] The data length does not match as expected!";
138 return "[RxPacketError] The data value exceeds the limit value!";
141 return "[RxPacketError] Writing or Reading is not available to target address!";
144 return "[RxPacketError] Unknown error code!";
148 unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size)
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 };
190 for (uint16_t j = 0; j < data_blk_size; j++)
192 i = ((uint16_t)(crc_accum >> 8) ^ *data_blk_ptr++) & 0xFF;
193 crc_accum = (crc_accum << 8) ^ crc_table[i];
199 void Protocol2PacketHandler::addStuffing(uint8_t *packet)
202 int packet_length_out = packet_length_in;
204 if (packet_length_in < 8)
208 uint16_t packet_length_before_crc = packet_length_in - 2;
209 for (uint16_t i = 3; i < packet_length_before_crc; i++)
212 if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD)
216 if (packet_length_in == packet_length_out)
219 uint16_t out_index = packet_length_out + 6 - 2;
220 uint16_t in_index = packet_length_in + 6 - 2;
221 while (out_index != in_index)
223 if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF)
225 packet[out_index--] = 0xFD;
226 if (out_index != in_index)
228 packet[out_index--] = packet[in_index--];
229 packet[out_index--] = packet[in_index--];
230 packet[out_index--] = packet[in_index--];
235 packet[out_index--] = packet[in_index--];
245 void Protocol2PacketHandler::removeStuffing(uint8_t *packet)
247 int i = 0, index = 0;
249 int packet_length_out = packet_length_in;
252 for (i = 0; i < packet_length_in - 2; i++)
270 uint16_t total_packet_length = 0;
271 uint16_t written_packet_length = 0;
278 addStuffing(txpacket);
296 uint16_t crc = updateCRC(0, txpacket, total_packet_length - 2);
297 txpacket[total_packet_length - 2] =
MCY_LOBYTE(crc);
298 txpacket[total_packet_length - 1] =
MCY_HIBYTE(crc);
302 written_packet_length = port->
writePort(txpacket, total_packet_length);
303 if (total_packet_length != written_packet_length)
316 uint16_t rx_length = 0;
317 uint16_t wait_length = 11;
321 rx_length += port->
readPort(&rxpacket[rx_length], wait_length - rx_length);
322 if (rx_length >= wait_length)
327 for (idx = 0; idx < (rx_length - 3); idx++)
329 if ((rxpacket[idx] == 0xFF) && (rxpacket[idx+1] == 0xFF) && (rxpacket[idx+2] == 0xFD) && (rxpacket[idx+3] != 0xFD))
336 rxpacket[
PKT_ID] > 0xFC ||
341 for (uint16_t s = 0; s < rx_length - 1; s++)
342 rxpacket[s] = rxpacket[1 + s];
355 if (rx_length < wait_length)
377 uint16_t crc =
MCY_MAKEWORD(rxpacket[wait_length-2], rxpacket[wait_length-1]);
378 if (updateCRC(0, rxpacket, wait_length - 2) == crc)
391 for (uint16_t s = 0; s < rx_length - idx; s++)
392 rxpacket[s] = rxpacket[idx + s];
413 #if defined(__linux__) || defined(__APPLE__)
415 #elif defined(_WIN32) || defined(_WIN64)
422 removeStuffing(rxpacket);
470 return ping(port,
id, 0, error);
477 uint8_t txpacket[10] = {0};
478 uint8_t rxpacket[14] = {0};
488 result =
txRxPacket(port, txpacket, rxpacket, error);
497 const int STATUS_LENGTH = 14;
502 uint16_t rx_length = 0;
503 uint16_t wait_length = STATUS_LENGTH *
MAX_ID;
505 uint8_t txpacket[10] = {0};
506 uint8_t rxpacket[STATUS_LENGTH *
MAX_ID] = {0};
508 double tx_time_per_byte = (1000.0 / (double)port->
getBaudRate()) * 10.0;
527 rx_length += port->
readPort(&rxpacket[rx_length], wait_length - rx_length);
539 if (rx_length < STATUS_LENGTH)
545 for (idx = 0; idx < (rx_length - 2); idx++)
547 if (rxpacket[idx] == 0xFF && rxpacket[idx+1] == 0xFF && rxpacket[idx+2] == 0xFD)
554 uint16_t crc =
MCY_MAKEWORD(rxpacket[STATUS_LENGTH-2], rxpacket[STATUS_LENGTH-1]);
556 if (updateCRC(0, rxpacket, STATUS_LENGTH - 2) == crc)
560 id_list.push_back(rxpacket[
PKT_ID]);
562 for (uint16_t s = 0; s < rx_length - STATUS_LENGTH; s++)
563 rxpacket[s] = rxpacket[STATUS_LENGTH + s];
564 rx_length -= STATUS_LENGTH;
574 for (uint16_t s = 0; s < rx_length - 3; s++)
575 rxpacket[s] = rxpacket[3 + s];
582 for (uint16_t s = 0; s < rx_length - idx; s++)
583 rxpacket[s] = rxpacket[idx + s];
593 uint8_t txpacket[10] = {0};
605 uint8_t txpacket[10] = {0};
606 uint8_t rxpacket[11] = {0};
613 return txRxPacket(port, txpacket, rxpacket, error);
618 uint8_t txpacket[15] = {0};
619 uint8_t rxpacket[11] = {0};
631 return txRxPacket(port, txpacket, rxpacket, error);
636 uint8_t txpacket[11] = {0};
637 uint8_t rxpacket[11] = {0};
645 return txRxPacket(port, txpacket, rxpacket, error);
652 uint8_t txpacket[14] = {0};
680 if (rxpacket == NULL)
692 for (uint16_t s = 0; s < length; s++)
706 uint8_t txpacket[14] = {0};
709 if (rxpacket == NULL)
727 result =
txRxPacket(port, txpacket, rxpacket, error);
733 for (uint16_t s = 0; s < length; s++)
745 return readTx(port,
id, address, 1);
749 uint8_t data_read[1] = {0};
750 int result =
readRx(port,
id, 1, data_read, error);
752 *data = data_read[0];
757 uint8_t data_read[1] = {0};
758 int result =
readTxRx(port,
id, address, 1, data_read, error);
760 *data = data_read[0];
766 return readTx(port,
id, address, 2);
770 uint8_t data_read[2] = {0};
771 int result =
readRx(port,
id, 2, data_read, error);
778 uint8_t data_read[2] = {0};
779 int result =
readTxRx(port,
id, address, 2, data_read, error);
787 return readTx(port,
id, address, 4);
791 uint8_t data_read[4] = {0};
792 int result =
readRx(port,
id, 4, data_read, error);
799 uint8_t data_read[4] = {0};
800 int result =
readTxRx(port,
id, address, 4, data_read, error);
810 uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
812 if (txpacket == NULL)
822 for (uint16_t s = 0; s < length; s++)
836 uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
837 uint8_t rxpacket[11] = {0};
839 if (txpacket == NULL)
849 for (uint16_t s = 0; s < length; s++)
852 result =
txRxPacket(port, txpacket, rxpacket, error);
860 uint8_t data_write[1] = { data };
861 return writeTxOnly(port,
id, address, 1, data_write);
865 uint8_t data_write[1] = { data };
866 return writeTxRx(port,
id, address, 1, data_write, error);
872 return writeTxOnly(port,
id, address, 2, data_write);
877 return writeTxRx(port,
id, address, 2, data_write, error);
883 return writeTxOnly(port,
id, address, 4, data_write);
888 return writeTxRx(port,
id, address, 4, data_write, error);
895 uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
897 if (txpacket == NULL)
907 for (uint16_t s = 0; s < length; s++)
921 uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3));
922 uint8_t rxpacket[11] = {0};
924 if (txpacket == NULL)
934 for (uint16_t s = 0; s < length; s++)
937 result =
txRxPacket(port, txpacket, rxpacket, error);
947 uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3));
950 if (txpacket == NULL)
962 for (uint16_t s = 0; s < param_length; s++)
977 uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3));
979 if (txpacket == NULL)
991 for (uint16_t s = 0; s < param_length; s++)
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;
1006 uint8_t mcy_hardware_status = 0;
1009 bool is_synchronising =
false;
1013 mcy_comm_result =
read1ByteTxRx(port,
id, ADDR_MX_HARDWARE_STATUS_L, &mcy_hardware_status, error);
1016 return mcy_comm_result;
1019 if (mcy_hardware_status & 0x02)
1021 if (is_synchronising)
1024 #if defined(__linux__)
1030 mcy_comm_result =
write1ByteTxRx(port,
id, ADDR_MCY_CONTROL_ENABLE, synchronise_enable, error);
1033 return mcy_comm_result;
1035 is_synchronising =
true;
1038 }
while (mcy_hardware_status & synchronise_enable);
1040 return mcy_comm_result;
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
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
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 INST_FACTORY_RESET
#define MCY_MAKEDWORD(a, b)
#define COMM_NOT_AVAILABLE
#define MCY_MAKEWORD(a, b)
#define ERRNUM_RESULT_FAIL
#define ERRNUM_DATA_LENGTH
#define ERRNUM_INSTRUCTION
#define ERRNUM_DATA_LIMIT
#define ERRNUM_DATA_RANGE