protocol2_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_PROTOCOL2PACKETHANDLER_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_
00024 
00025 
00026 #include "packet_handler.h"
00027 
00028 namespace dynamixel
00029 {
00030 
00034 class WINDECLSPEC Protocol2PacketHandler : public PacketHandler
00035 {
00036  private:
00037   static Protocol2PacketHandler *unique_instance_;
00038 
00039   Protocol2PacketHandler();
00040 
00041   uint16_t    updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size);
00042   void        addStuffing(uint8_t *packet);
00043   void        removeStuffing(uint8_t *packet);
00044 
00045  public:
00050   static Protocol2PacketHandler *getInstance() { return unique_instance_; }
00051 
00052   virtual ~Protocol2PacketHandler() { }
00053 
00058   float   getProtocolVersion() { return 2.0; }
00059 
00065   const char *getTxRxResult     (int result);
00066 
00072   const char *getRxPacketError  (uint8_t error);
00073 
00089   int txPacket        (PortHandler *port, uint8_t *txpacket);
00090 
00110   int rxPacket        (PortHandler *port, uint8_t *rxpacket);
00111 
00126   int txRxPacket      (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
00127 
00137   int ping            (PortHandler *port, uint8_t id, uint8_t *error = 0);
00138 
00155   int ping            (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0);
00156 
00163   int broadcastPing   (PortHandler *port, std::vector<uint8_t> &id_list);
00164 
00174   int action          (PortHandler *port, uint8_t id);
00175 
00187   int reboot          (PortHandler *port, uint8_t id, uint8_t *error = 0);
00188 
00200   int factoryReset    (PortHandler *port, uint8_t id, uint8_t option, uint8_t *error = 0);
00201 
00216   int readTx          (PortHandler *port, uint8_t id, uint16_t address, uint16_t length);
00217 
00228   int readRx          (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0);
00229 
00247   int readTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00248 
00257   int read1ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00258 
00268   int read1ByteRx     (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0);
00269 
00282   int read1ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0);
00283 
00292   int read2ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00293 
00303   int read2ByteRx     (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0);
00304 
00317   int read2ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0);
00318 
00327   int read4ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00328 
00338   int read4ByteRx     (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0);
00339 
00352   int read4ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0);
00353 
00365   int writeTxOnly     (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
00366 
00380   int writeTxRx           (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00381 
00391   int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data);
00392 
00404   int write1ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0);
00405 
00415   int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data);
00416 
00428   int write2ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0);
00429 
00439   int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data);
00440 
00452   int write4ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0);
00453 
00466   int regWriteTxOnly  (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
00467 
00482   int regWriteTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00483 
00484 
00496   int syncReadTx      (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
00497   // SyncReadRx   -> GroupSyncRead class
00498   // SyncReadTxRx -> GroupSyncRead class
00499 
00511   int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
00512 
00522   int bulkReadTx      (PortHandler *port, uint8_t *param, uint16_t param_length);
00523   // BulkReadRx   -> GroupBulkRead class
00524   // BulkReadTxRx -> GroupBulkRead class
00525 
00535   int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length);
00536 };
00537 
00538 }
00539 
00540 
00541 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_ */


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