22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ 23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ 25 #if defined(__linux__) 27 #elif defined(__APPLE__) 29 #elif defined(_WIN32) || defined(_WIN64) 31 #define WINDECLSPEC __declspec(dllexport) 33 #define WINDECLSPEC __declspec(dllimport) 35 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) 40 #define DEPRECATED __attribute__((deprecated)) 41 #elif defined(_MSC_VER) 42 #define DEPRECATED __declspec(deprecated) 44 #pragma message("WARNING: You need to implement DEPRECATED for this compiler") 59 static const int DEFAULT_BAUDRATE_ = 57600;
65 static PortHandler *getPortHandler(
const char *port_name);
76 virtual bool openPort() = 0;
82 virtual void closePort() = 0;
88 virtual void clearPort() = 0;
95 virtual void setPortName(
const char* port_name) = 0;
102 virtual char *getPortName() = 0;
112 virtual bool setBaudRate(
const int baudrate) = 0;
119 virtual int getBaudRate() = 0;
127 virtual int getBytesAvailable() = 0;
139 virtual int readPort(uint8_t *packet,
int length) = 0;
151 virtual int writePort(uint8_t *packet,
int length) = 0;
158 virtual void setPacketTimeout(uint16_t packet_length) = 0;
165 virtual void setPacketTimeout(
double msec) = 0;
171 virtual bool isPacketTimeout() = 0;
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
bool is_using_
shows whether the port is in use