packet_handler.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
21 
22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
24 
25 #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
26 #include <Arduino.h>
27 
28 #define ERROR_PRINT SerialBT2.print
29 #else
30 #define ERROR_PRINT printf
31 
32 #endif
33 
34 #include <stdio.h>
35 #include <vector>
36 #include "port_handler.h"
37 
38 #define BROADCAST_ID 0xFE // 254
39 #define MAX_ID 0xFC // 252
40 
41 /* Macro for Control Table Value */
42 #define DXL_MAKEWORD(a, b) ((uint16_t)(((uint8_t)(((uint64_t)(a)) & 0xff)) | ((uint16_t)((uint8_t)(((uint64_t)(b)) & 0xff))) << 8))
43 #define DXL_MAKEDWORD(a, b) ((uint32_t)(((uint16_t)(((uint64_t)(a)) & 0xffff)) | ((uint32_t)((uint16_t)(((uint64_t)(b)) & 0xffff))) << 16))
44 #define DXL_LOWORD(l) ((uint16_t)(((uint64_t)(l)) & 0xffff))
45 #define DXL_HIWORD(l) ((uint16_t)((((uint64_t)(l)) >> 16) & 0xffff))
46 #define DXL_LOBYTE(w) ((uint8_t)(((uint64_t)(w)) & 0xff))
47 #define DXL_HIBYTE(w) ((uint8_t)((((uint64_t)(w)) >> 8) & 0xff))
48 
49 /* Instruction for DXL Protocol */
50 #define INST_PING 1
51 #define INST_READ 2
52 #define INST_WRITE 3
53 #define INST_REG_WRITE 4
54 #define INST_ACTION 5
55 #define INST_FACTORY_RESET 6
56 #define INST_SYNC_WRITE 131 // 0x83
57 #define INST_BULK_READ 146 // 0x92
58 // --- Only for 2.0 --- //
59 #define INST_REBOOT 8
60 #define INST_CLEAR 16 // 0x10
61 #define INST_STATUS 85 // 0x55
62 #define INST_SYNC_READ 130 // 0x82
63 #define INST_BULK_WRITE 147 // 0x93
64 
65 // Communication Result
66 #define COMM_SUCCESS 0 // tx or rx packet communication success
67 #define COMM_PORT_BUSY -1000 // Port is busy (in use)
68 #define COMM_TX_FAIL -1001 // Failed transmit instruction packet
69 #define COMM_RX_FAIL -1002 // Failed get status packet
70 #define COMM_TX_ERROR -2000 // Incorrect instruction packet
71 #define COMM_RX_WAITING -3000 // Now recieving status packet
72 #define COMM_RX_TIMEOUT -3001 // There is no status packet
73 #define COMM_RX_CORRUPT -3002 // Incorrect status packet
74 #define COMM_NOT_AVAILABLE -9000 //
75 
76 namespace dynamixel
77 {
78 
82 class WINDECLSPEC PacketHandler
83 {
84  protected:
86 
87  public:
92  static PacketHandler *getPacketHandler(float protocol_version = 2.0);
93 
94  virtual ~PacketHandler() { }
95 
100  virtual float getProtocolVersion() = 0;
101 
107  virtual const char *getTxRxResult (int result) = 0;
108 
114  virtual const char *getRxPacketError (uint8_t error) = 0;
115 
131  virtual int txPacket (PortHandler *port, uint8_t *txpacket) = 0;
132 
152  virtual int rxPacket (PortHandler *port, uint8_t *rxpacket) = 0;
153 
168  virtual int txRxPacket (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0) = 0;
169 
179  virtual int ping (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
180 
197  virtual int ping (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0) = 0;
198 
205  virtual int broadcastPing (PortHandler *port, std::vector<uint8_t> &id_list) = 0;
206 
216  virtual int action (PortHandler *port, uint8_t id) = 0;
217 
229  virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
230 
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  // SyncReadRx -> GroupSyncRead class
552  // SyncReadTxRx -> GroupSyncRead class
553 
565  virtual int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
566 
576  virtual int bulkReadTx (PortHandler *port, uint8_t *param, uint16_t param_length) = 0;
577  // BulkReadRx -> GroupBulkRead class
578  // BulkReadTxRx -> GroupBulkRead class
579 
589  virtual int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length) = 0;
590 };
591 
592 }
593 
594 
595 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ */
bool param(const std::string &param_name, T &param_val, const T &default_val)
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55