protocol1_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_PROTOCOL1PACKETHANDLER_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
00024 
00025 
00026 #include "packet_handler.h"
00027 
00028 namespace dynamixel
00029 {
00030 
00034 class WINDECLSPEC Protocol1PacketHandler : public PacketHandler
00035 {
00036  private:
00037   static Protocol1PacketHandler *unique_instance_;
00038 
00039   Protocol1PacketHandler();
00040 
00041  public:
00046   static Protocol1PacketHandler *getInstance() { return unique_instance_; }
00047 
00048   virtual ~Protocol1PacketHandler() { }
00049 
00054   float   getProtocolVersion() { return 1.0; }
00055 
00061   const char *getTxRxResult     (int result);
00062 
00068   const char *getRxPacketError  (uint8_t error);
00069 
00085   int txPacket        (PortHandler *port, uint8_t *txpacket);
00086 
00106   int rxPacket        (PortHandler *port, uint8_t *rxpacket);
00107 
00122   int txRxPacket      (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
00123 
00133   int ping            (PortHandler *port, uint8_t id, uint8_t *error = 0);
00134 
00151   int ping            (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0);
00152 
00159   int broadcastPing   (PortHandler *port, std::vector<uint8_t> &id_list);
00160 
00170   int action          (PortHandler *port, uint8_t id);
00171 
00179   int reboot          (PortHandler *port, uint8_t id, uint8_t *error = 0);
00180 
00192   int factoryReset    (PortHandler *port, uint8_t id, uint8_t option, uint8_t *error = 0);
00193 
00208   int readTx          (PortHandler *port, uint8_t id, uint16_t address, uint16_t length);
00209 
00220   int readRx          (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0);
00221 
00239   int readTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00240 
00249   int read1ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00250 
00260   int read1ByteRx     (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0);
00261 
00274   int read1ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0);
00275 
00284   int read2ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00285 
00295   int read2ByteRx     (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0);
00296 
00309   int read2ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0);
00310 
00319   int read4ByteTx     (PortHandler *port, uint8_t id, uint16_t address);
00320 
00330   int read4ByteRx     (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0);
00331 
00344   int read4ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0);
00345 
00357   int writeTxOnly     (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
00358 
00372   int writeTxRx           (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00373 
00383   int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data);
00384 
00396   int write1ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0);
00397 
00407   int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data);
00408 
00420   int write2ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0);
00421 
00431   int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data);
00432 
00444   int write4ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0);
00445 
00458   int regWriteTxOnly  (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
00459 
00474   int regWriteTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
00475 
00485   int syncReadTx      (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
00486   // SyncReadRx   -> GroupSyncRead class
00487   // SyncReadTxRx -> GroupSyncRead class
00488 
00500   int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
00501 
00511   int bulkReadTx      (PortHandler *port, uint8_t *param, uint16_t param_length);
00512   // BulkReadRx   -> GroupBulkRead class
00513   // BulkReadTxRx -> GroupBulkRead class
00514 
00522   int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length);
00523 };
00524 
00525 }
00526 
00527 
00528 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_ */


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