Program Listing for File protocol1_packet_handler.h

Return to documentation for file (/tmp/ws/src/dynamixel_sdk/dynamixel_sdk/include/dynamixel_sdk/protocol1_packet_handler.h)

/*******************************************************************************
* Copyright 2017 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*     http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/


#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_


#include "packet_handler.h"

namespace dynamixel
{

class WINDECLSPEC Protocol1PacketHandler : public PacketHandler
{
 private:
  static Protocol1PacketHandler *unique_instance_;

  Protocol1PacketHandler();

 public:
  static Protocol1PacketHandler *getInstance() { return unique_instance_; }

  virtual ~Protocol1PacketHandler() { }

  float   getProtocolVersion() { return 1.0; }

  const char *getTxRxResult     (int result);

  const char *getRxPacketError  (uint8_t error);

  int txPacket        (PortHandler *port, uint8_t *txpacket);

  int rxPacket        (PortHandler *port, uint8_t *rxpacket);

  int txRxPacket      (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);

  int ping            (PortHandler *port, uint8_t id, uint8_t *error = 0);

  int ping            (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0);

  int broadcastPing   (PortHandler *port, std::vector<uint8_t> &id_list);

  int action          (PortHandler *port, uint8_t id);

  int reboot          (PortHandler *port, uint8_t id, uint8_t *error = 0);

  int clearMultiTurn  (PortHandler *port, uint8_t id, uint8_t *error = 0);

  int factoryReset    (PortHandler *port, uint8_t id, uint8_t option, uint8_t *error = 0);

  int readTx          (PortHandler *port, uint8_t id, uint16_t address, uint16_t length);

  int readRx          (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0);

  int readTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);

  int read1ByteTx     (PortHandler *port, uint8_t id, uint16_t address);

  int read1ByteRx     (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0);

  int read1ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0);

  int read2ByteTx     (PortHandler *port, uint8_t id, uint16_t address);

  int read2ByteRx     (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0);

  int read2ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0);

  int read4ByteTx     (PortHandler *port, uint8_t id, uint16_t address);

  int read4ByteRx     (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0);

  int read4ByteTxRx       (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0);

  int writeTxOnly     (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);

  int writeTxRx           (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);

  int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data);

  int write1ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0);

  int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data);

  int write2ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0);

  int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data);

  int write4ByteTxRx      (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0);

  int regWriteTxOnly  (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);

  int regWriteTxRx        (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);

  int syncReadTx      (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
  // SyncReadRx   -> GroupSyncRead class
  // SyncReadTxRx -> GroupSyncRead class

  int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);

  int bulkReadTx      (PortHandler *port, uint8_t *param, uint16_t param_length);
  // BulkReadRx   -> GroupBulkRead class
  // BulkReadTxRx -> GroupBulkRead class

  int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length);
};

}


#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_ */