MercurySDK
Software development kit for Mercury digital servos
packet_handler.h
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 #ifndef INCLUDE_MERCURY_SDK_PACKETHANDLER_H_
26 #define INCLUDE_MERCURY_SDK_PACKETHANDLER_H_
27 
28 #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
29 #include <Arduino.h>
30 
31 #define ERROR_PRINT SerialBT2.print
32 #else
33 #define ERROR_PRINT printf
34 
35 #endif
36 
37 #include <stdio.h>
38 #include <vector>
39 #include <functional>
40 #include <string>
41 #include "port_handler.h"
42 
43 #define BROADCAST_ID 0xFE // 254
44 #define MAX_ID 0xFC // 252
45 
46 /* Macro for Control Table Value */
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))
53 
54 /* Instruction for DXL Protocol */
55 #define INST_PING 1
56 #define INST_READ 2
57 #define INST_WRITE 3
58 #define INST_REG_WRITE 4
59 #define INST_ACTION 5
60 #define INST_FACTORY_RESET 6
61 #define INST_SYNC_WRITE 131 // 0x83
62 #define INST_REBOOT 8
63 #define INST_CLEAR 16 // 0x10
64 #define INST_STATUS 85 // 0x55
65 #define INST_SYNC_READ 130 // 0x82
66 
67 // Communication Result
68 #define COMM_SUCCESS 0 // tx or rx packet communication success
69 #define COMM_PORT_BUSY -1000 // Port is busy (in use)
70 #define COMM_TX_FAIL -1001 // Failed transmit instruction packet
71 #define COMM_RX_FAIL -1002 // Failed get status packet
72 #define COMM_TX_ERROR -2000 // Incorrect instruction packet
73 #define COMM_RX_WAITING -3000 // Now recieving status packet
74 #define COMM_RX_TIMEOUT -3001 // There is no status packet
75 #define COMM_RX_CORRUPT -3002 // Incorrect status packet
76 #define COMM_NOT_AVAILABLE -9000 //
77 
78 namespace mercury
79 {
80 
84 class WINDECLSPEC PacketHandler
85 {
86  protected:
88 
89  public:
94  static PacketHandler *getPacketHandler();
95 
96  virtual ~PacketHandler() { }
97 
102  virtual float getProtocolVersion() = 0;
103 
109  virtual const char *getTxRxResult (int result) = 0;
110 
116  virtual const char *getRxPacketError (uint8_t error) = 0;
117 
133  virtual int txPacket (PortHandler *port, uint8_t *txpacket) = 0;
134 
154  virtual int rxPacket (PortHandler *port, uint8_t *rxpacket) = 0;
155 
170  virtual int txRxPacket (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0) = 0;
171 
181  virtual int ping (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
182 
199  virtual int ping (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0) = 0;
200 
207  virtual int broadcastPing (PortHandler *port, std::vector<uint8_t> &id_list) = 0;
208 
218  virtual int action (PortHandler *port, uint8_t id) = 0;
219 
231  virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
232 
242  virtual int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
243 
255  virtual int factoryReset (PortHandler *port, uint8_t id, uint8_t option = 0, uint8_t *error = 0) = 0;
256 
271  virtual int readTx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length) = 0;
272 
283  virtual int readRx (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
284 
302  virtual int readTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
303 
312  virtual int read1ByteTx (PortHandler *port, uint8_t id, uint16_t address) = 0;
313 
323  virtual int read1ByteRx (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0) = 0;
324 
337  virtual int read1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0) = 0;
338 
347  virtual int read2ByteTx (PortHandler *port, uint8_t id, uint16_t address) = 0;
348 
358  virtual int read2ByteRx (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0) = 0;
359 
372  virtual int read2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0) = 0;
373 
382  virtual int read4ByteTx (PortHandler *port, uint8_t id, uint16_t address) = 0;
383 
393  virtual int read4ByteRx (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0) = 0;
394 
407  virtual int read4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0) = 0;
408 
420  virtual int writeTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) = 0;
421 
435  virtual int writeTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
436 
446  virtual int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data) = 0;
447 
459  virtual int write1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0) = 0;
460 
470  virtual int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data) = 0;
471 
483  virtual int write2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0) = 0;
484 
494  virtual int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data) = 0;
495 
507  virtual int write4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0) = 0;
508 
521  virtual int regWriteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) = 0;
522 
537  virtual int regWriteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
538 
550  virtual int syncReadTx (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
551 
563  virtual int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
564 
575  virtual int synchronise (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
576 
577 };
578 
579 }
580 
581 
582 #endif /* INCLUDE_MERCURY_SDK_PACKETHANDLER_H_ */
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,...
Definition: port_handler.h:56