packet_handler.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * Copyright 2017 ROBOTIS CO., LTD.
00003 *
00004 * Licensed under the Apache License, Version 2.0 (the "License");
00005 * you may not use this file except in compliance with the License.
00006 * You may obtain a copy of the License at
00007 *
00008 *     http://www.apache.org/licenses/LICENSE-2.0
00009 *
00010 * Unless required by applicable law or agreed to in writing, software
00011 * distributed under the License is distributed on an "AS IS" BASIS,
00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013 * See the License for the specific language governing permissions and
00014 * limitations under the License.
00015 *******************************************************************************/
00016 
00021 
00022 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
00024 
00025 #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
00026 #include <Arduino.h>
00027 #endif
00028 
00029 #include <stdio.h>
00030 #include <vector>
00031 #include "port_handler.h"
00032 
00033 #define BROADCAST_ID        0xFE    // 254
00034 #define MAX_ID              0xFC    // 252
00035 
00036 /* Macro for Control Table Value */
00037 #define DXL_MAKEWORD(a, b)  ((uint16_t)(((uint8_t)(((uint64_t)(a)) & 0xff)) | ((uint16_t)((uint8_t)(((uint64_t)(b)) & 0xff))) << 8))
00038 #define DXL_MAKEDWORD(a, b) ((uint32_t)(((uint16_t)(((uint64_t)(a)) & 0xffff)) | ((uint32_t)((uint16_t)(((uint64_t)(b)) & 0xffff))) << 16))
00039 #define DXL_LOWORD(l)       ((uint16_t)(((uint64_t)(l)) & 0xffff))
00040 #define DXL_HIWORD(l)       ((uint16_t)((((uint64_t)(l)) >> 16) & 0xffff))
00041 #define DXL_LOBYTE(w)       ((uint8_t)(((uint64_t)(w)) & 0xff))
00042 #define DXL_HIBYTE(w)       ((uint8_t)((((uint64_t)(w)) >> 8) & 0xff))
00043 
00044 /* Instruction for DXL Protocol */
00045 #define INST_PING               1
00046 #define INST_READ               2
00047 #define INST_WRITE              3
00048 #define INST_REG_WRITE          4
00049 #define INST_ACTION             5
00050 #define INST_FACTORY_RESET      6
00051 #define INST_SYNC_WRITE         131     // 0x83
00052 #define INST_BULK_READ          146     // 0x92
00053 // --- Only for 2.0 --- //
00054 #define INST_REBOOT             8
00055 #define INST_STATUS             85      // 0x55
00056 #define INST_SYNC_READ          130     // 0x82
00057 #define INST_BULK_WRITE         147     // 0x93
00058 
00059 // Communication Result
00060 #define COMM_SUCCESS        0       // tx or rx packet communication success
00061 #define COMM_PORT_BUSY      -1000   // Port is busy (in use)
00062 #define COMM_TX_FAIL        -1001   // Failed transmit instruction packet
00063 #define COMM_RX_FAIL        -1002   // Failed get status packet
00064 #define COMM_TX_ERROR       -2000   // Incorrect instruction packet
00065 #define COMM_RX_WAITING     -3000   // Now recieving status packet
00066 #define COMM_RX_TIMEOUT     -3001   // There is no status packet
00067 #define COMM_RX_CORRUPT     -3002   // Incorrect status packet
00068 #define COMM_NOT_AVAILABLE  -9000   //
00069 
00070 namespace dynamixel
00071 {
00072 
00076 class WINDECLSPEC PacketHandler
00077 {
00078  protected:
00079   PacketHandler() { }
00080 
00081  public:
00086   static PacketHandler *getPacketHandler(float protocol_version = 2.0);
00087 
00088   virtual ~PacketHandler() { }
00089 
00094   virtual float   getProtocolVersion() = 0;
00095 
00101   virtual const char *getTxRxResult     (int result) = 0;
00102 
00108   virtual const char *getRxPacketError  (uint8_t error) = 0;
00109 
00125   virtual int txPacket        (PortHandler *port, uint8_t *txpacket) = 0;
00126 
00146   virtual int rxPacket        (PortHandler *port, uint8_t *rxpacket) = 0;
00147 
00162   virtual int txRxPacket      (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0) = 0;
00163 
00173   virtual int ping            (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
00174 
00191   virtual int ping            (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0) = 0;
00192 
00199   virtual int broadcastPing   (PortHandler *port, std::vector<uint8_t> &id_list) = 0;
00200 
00210   virtual int action          (PortHandler *port, uint8_t id) = 0;
00211 
00223   virtual int reboot          (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0;
00224 
00236   virtual int factoryReset    (PortHandler *port, uint8_t id, uint8_t option = 0, uint8_t *error = 0) = 0;
00237 
00252   virtual int readTx          (PortHandler *port, uint8_t id, uint16_t address, uint16_t length) = 0;
00253 
00264   virtual int readRx          (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
00265 
00283   virtual int readTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
00284 
00293   virtual int read1ByteTx     (PortHandler *port, uint8_t id, uint16_t address) = 0;
00294 
00304   virtual int read1ByteRx     (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0) = 0;
00305 
00318   virtual int read1ByteTxRx   (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0) = 0;
00319 
00328   virtual int read2ByteTx     (PortHandler *port, uint8_t id, uint16_t address) = 0;
00329 
00339   virtual int read2ByteRx     (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0) = 0;
00340 
00353   virtual int read2ByteTxRx   (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0) = 0;
00354 
00363   virtual int read4ByteTx     (PortHandler *port, uint8_t id, uint16_t address) = 0;
00364 
00374   virtual int read4ByteRx     (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0) = 0;
00375 
00388   virtual int read4ByteTxRx   (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0) = 0;
00389 
00401   virtual int writeTxOnly     (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) = 0;
00402 
00416   virtual int writeTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
00417 
00427   virtual int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data) = 0;
00428 
00440   virtual int write1ByteTxRx  (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0) = 0;
00441 
00451   virtual int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data) = 0;
00452 
00464   virtual int write2ByteTxRx  (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0) = 0;
00465 
00475   virtual int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data) = 0;
00476 
00488   virtual int write4ByteTxRx  (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0) = 0;
00489 
00502   virtual int regWriteTxOnly  (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) = 0;
00503 
00518   virtual int regWriteTxRx    (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0) = 0;
00519 
00531   virtual int syncReadTx      (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
00532   // SyncReadRx   -> GroupSyncRead class
00533   // SyncReadTxRx -> GroupSyncRead class
00534 
00546   virtual int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) = 0;
00547 
00557   virtual int bulkReadTx      (PortHandler *port, uint8_t *param, uint16_t param_length) = 0;
00558   // BulkReadRx   -> GroupBulkRead class
00559   // BulkReadTxRx -> GroupBulkRead class
00560 
00570   virtual int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length) = 0;
00571 };
00572 
00573 }
00574 
00575 
00576 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ */


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11