Program Listing for File port_handler.h

Return to documentation for file (/tmp/ws/src/dynamixel_sdk/dynamixel_sdk/include/dynamixel_sdk/port_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_PORTHANDLER_H_
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_

#if defined(__linux__)
#define WINDECLSPEC
#elif defined(__APPLE__)
#define WINDECLSPEC
#elif defined(_WIN32) || defined(_WIN64)
  #ifdef WINDLLEXPORT
  #define WINDECLSPEC __declspec(dllexport)
  #else
  #define WINDECLSPEC __declspec(dllimport)
  #endif
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
#define WINDECLSPEC
#endif

#ifdef __GNUC__
#define DEPRECATED __attribute__((deprecated))
#elif defined(_MSC_VER)
#define DEPRECATED __declspec(deprecated)
#else
#pragma message("WARNING: You need to implement DEPRECATED for this compiler")
#define DEPRECATED
#endif

#include <stdint.h>

namespace dynamixel
{

class WINDECLSPEC PortHandler
{
 public:
  static const int DEFAULT_BAUDRATE_ = 57600;

  static PortHandler *getPortHandler(const char *port_name);

  bool   is_using_;

  virtual ~PortHandler() { }

  virtual bool    openPort() = 0;

  virtual void    closePort() = 0;

  virtual void    clearPort() = 0;

  virtual void    setPortName(const char* port_name) = 0;

  virtual char   *getPortName() = 0;

  virtual bool    setBaudRate(const int baudrate) = 0;

  virtual int     getBaudRate() = 0;

  virtual int     getBytesAvailable() = 0;

  virtual int     readPort(uint8_t *packet, int length) = 0;

  virtual int     writePort(uint8_t *packet, int length) = 0;

  virtual void    setPacketTimeout(uint16_t packet_length) = 0;

  virtual void    setPacketTimeout(double msec) = 0;

  virtual bool    isPacketTimeout() = 0;
};

}


#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ */