25 #ifndef INCLUDE_MERCURY_SDK_PACKETHANDLER_H_
26 #define INCLUDE_MERCURY_SDK_PACKETHANDLER_H_
28 #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
31 #define ERROR_PRINT SerialBT2.print
33 #define ERROR_PRINT printf
43 #define BROADCAST_ID 0xFE
47 #define MCY_MAKEWORD(a, b) ((uint16_t)(((uint8_t)(((uint64_t)(a)) & 0xff)) | ((uint16_t)((uint8_t)(((uint64_t)(b)) & 0xff))) << 8))
48 #define MCY_MAKEDWORD(a, b) ((uint32_t)(((uint16_t)(((uint64_t)(a)) & 0xffff)) | ((uint32_t)((uint16_t)(((uint64_t)(b)) & 0xffff))) << 16))
49 #define MCY_LOWORD(l) ((uint16_t)(((uint64_t)(l)) & 0xffff))
50 #define MCY_HIWORD(l) ((uint16_t)((((uint64_t)(l)) >> 16) & 0xffff))
51 #define MCY_LOBYTE(w) ((uint8_t)(((uint64_t)(w)) & 0xff))
52 #define MCY_HIBYTE(w) ((uint8_t)((((uint64_t)(w)) >> 8) & 0xff))
58 #define INST_REG_WRITE 4
60 #define INST_FACTORY_RESET 6
61 #define INST_SYNC_WRITE 131
64 #define INST_STATUS 85
65 #define INST_SYNC_READ 130
68 #define COMM_SUCCESS 0
69 #define COMM_PORT_BUSY -1000
70 #define COMM_TX_FAIL -1001
71 #define COMM_RX_FAIL -1002
72 #define COMM_TX_ERROR -2000
73 #define COMM_RX_WAITING -3000
74 #define COMM_RX_TIMEOUT -3001
75 #define COMM_RX_CORRUPT -3002
76 #define COMM_NOT_AVAILABLE -9000
199 virtual int ping (
PortHandler *port, uint8_t
id, uint16_t *model_number, uint8_t *error = 0) = 0;
283 virtual int readRx (
PortHandler *port, uint8_t
id, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
302 virtual int readTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
435 virtual int writeTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
537 virtual int regWriteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
550 virtual int syncReadTx (
PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
virtual int read1ByteRx(PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readRx() function and reads 1 byte data on the packet @descrip...
virtual int rxPacket(PortHandler *port, uint8_t *rxpacket)=0
The function that receives packet (rxpacket) during designated time via PortHandler port @description...
virtual int factoryReset(PortHandler *port, uint8_t id, uint8_t option=0, uint8_t *error=0)=0
The function that makes Mercury reset as it was produced in the factory @description The function mak...
virtual int readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that receives the packet and reads the data in the packet @description The function rece...
virtual int regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)=0
The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Mercur...
virtual const char * getTxRxResult(int result)=0
The function that gets description of communication result.
virtual int read4ByteRx(PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readRx() function and reads 4 byte data on the packet @descrip...
virtual int ping(PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error=0)=0
The function that pings Mercury and takes its model number @description The function makes an instruc...
virtual int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data)=0
The function that calls PacketHandler::writeTxOnly() for writing 1 byte data @description The functio...
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
The function that calls PacketHandler::writeTxRx() for writing 1 byte data and receives the packet @d...
virtual int action(PortHandler *port, uint8_t id)=0
The function that makes Mercurys run as written in the Mercury register @description The function mak...
virtual int read1ByteTx(PortHandler *port, uint8_t id, uint16_t address)=0
The function that calls PacketHandler::readTx() function for reading 1 byte data @description The fun...
virtual int read2ByteRx(PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readRx() function and reads 2 byte data on the packet @descrip...
virtual int reboot(PortHandler *port, uint8_t id, uint8_t *error=0)=0
The function that makes Mercury reboot @description The function makes an instruction packet with INS...
virtual int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data)=0
The function that calls PacketHandler::writeTxOnly() for writing 2 byte data @description The functio...
virtual int readTx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length)=0
The function that transmits INST_READ instruction packet @description The function makes an instructi...
virtual int write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)=0
The function that calls PacketHandler::writeTxRx() for writing 2 byte data and receives the packet @d...
virtual const char * getRxPacketError(uint8_t error)=0
The function that gets description of hardware error.
virtual int ping(PortHandler *port, uint8_t id, uint8_t *error=0)=0
The function that pings Mercury but doesn't take its model number @description The function calls Pac...
virtual int read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)=0
The function that calls PacketHandler::readTx() function for reading 4 byte data @description The fun...
virtual int read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readTxRx() function for reading 1 byte data @description The f...
virtual int read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readTxRx() function for reading 4 byte data @description The f...
virtual int regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Mercur...
virtual int syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_SYNC_WRITE instruction packet @description The function makes an ins...
virtual int broadcastPing(PortHandler *port, std::vector< uint8_t > &id_list)=0
(Available only in Protocol 2.0) The function that pings all connected Mercury
virtual int clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error=0)=0
The function that resets the multi-turn revolution count @description The function makes an instructi...
virtual int synchronise(PortHandler *port, uint8_t id, uint8_t *error=0)=0
The function that synchronises the servo @description This function will synchronise the target Mercu...
virtual int readTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that transmits INST_READ instruction packet, and read data from received packet @descrip...
virtual int txRxPacket(PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error=0)=0
The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time v...
virtual int txPacket(PortHandler *port, uint8_t *txpacket)=0
The function that transmits the instruction packet txpacket via PortHandler port. @description The fu...
virtual int write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)=0
The function that calls PacketHandler::writeTxRx() for writing 4 byte data and receives the packet @d...
virtual int writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)=0
The function that transmits INST_WRITE instruction packet with the data for write @description The fu...
virtual float getProtocolVersion()=0
The function that returns Protocol version.
virtual int writeTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that transmits INST_WRITE instruction packet with the data for write,...
virtual int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)=0
The function that calls PacketHandler::writeTxOnly() for writing 4 byte data @description The functio...
virtual int read2ByteTx(PortHandler *port, uint8_t id, uint16_t address)=0
The function that calls PacketHandler::readTx() function for reading 2 byte data @description The fun...
virtual int read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0)=0
The function that calls PacketHandler::readTxRx() function for reading 2 byte data @description The f...
virtual int syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_SYNC_READ instruction packet @description The function makes an inst...
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...