MercurySDK
Software development kit for Mercury digital servos
port_handler.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (C) 2021 <Robot Articulation/code@robotarticulation.com>
3 *
4 * Source files modified to support the Mercury range of digital servo motors from Robot Articulation
5 *******************************************************************************/
6 
7 /*******************************************************************************
8 * Copyright 2017 ROBOTIS CO., LTD.
9 *
10 * Licensed under the Apache License, Version 2.0 (the "License");
11 * you may not use this file except in compliance with the License.
12 * You may obtain a copy of the License at
13 *
14 * http://www.apache.org/licenses/LICENSE-2.0
15 *
16 * Unless required by applicable law or agreed to in writing, software
17 * distributed under the License is distributed on an "AS IS" BASIS,
18 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19 * See the License for the specific language governing permissions and
20 * limitations under the License.
21 *******************************************************************************/
22 
23 /* Original author: Zerom, Leon (RyuWoon Jung) */
24 
25 #ifndef INCLUDE_MERCURY_SDK_PORTHANDLER_H_
26 #define INCLUDE_MERCURY_SDK_PORTHANDLER_H_
27 
28 #if defined(__linux__)
29 #define WINDECLSPEC
30 #elif defined(_WIN32) || defined(_WIN64)
31  #ifdef WINDLLEXPORT
32  #define WINDECLSPEC __declspec(dllexport)
33  #else
34  #define WINDECLSPEC __declspec(dllimport)
35  #endif
36 #endif
37 
38 #ifdef __GNUC__
39 #define DEPRECATED __attribute__((deprecated))
40 #elif defined(_MSC_VER)
41 #define DEPRECATED __declspec(deprecated)
42 #else
43 #pragma message("WARNING: You need to implement DEPRECATED for this compiler")
44 #define DEPRECATED
45 #endif
46 
47 #include <stdint.h>
48 
49 namespace mercury
50 {
51 
55 class WINDECLSPEC PortHandler
56 {
57  public:
58  static const int DEFAULT_BAUDRATE_ = 1000000;
59 
64  static PortHandler *getPortHandler(const char *port_name);
65 
66  bool is_using_;
67 
68  virtual ~PortHandler() { }
69 
75  virtual bool openPort() = 0;
76 
81  virtual void closePort() = 0;
82 
87  virtual void clearPort() = 0;
88 
94  virtual void setPortName(const char* port_name) = 0;
95 
101  virtual char *getPortName() = 0;
102 
111  virtual bool setBaudRate(const int baudrate) = 0;
112 
118  virtual int getBaudRate() = 0;
119 
126  virtual int getBytesAvailable() = 0;
127 
138  virtual int readPort(uint8_t *packet, int length) = 0;
139 
150  virtual int writePort(uint8_t *packet, int length) = 0;
151 
157  virtual void setPacketTimeout(uint16_t packet_length) = 0;
158 
164  virtual void setPacketTimeout(double msec) = 0;
165 
170  virtual bool isPacketTimeout() = 0;
171 };
172 
173 }
174 
175 
176 #endif /* INCLUDE_MERCURY_SDK_PORTHANDLER_H_ */
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition: port_handler.h:56
virtual int getBytesAvailable()=0
The function that checks how much bytes are able to be read from the port buffer @description The fun...
virtual bool openPort()=0
The function that opens the port @description The function calls PortHandlerLinux::setBaudRate() to o...
virtual bool setBaudRate(const int baudrate)=0
The function that sets baudrate into the port handler @description The function sets baudrate into th...
virtual bool isPacketTimeout()=0
The function that checks whether packet timeout is occurred @description The function checks whether ...
virtual int getBaudRate()=0
The function that returns current baudrate set into the port handler @description The function return...
virtual ~PortHandler()
Definition: port_handler.h:68
virtual char * getPortName()=0
The function that returns port name set into the port handler @description The function returns curre...
virtual void clearPort()=0
The function that clears the port @description The function clears the port.
bool is_using_
shows whether the port is in use
Definition: port_handler.h:66
virtual int writePort(uint8_t *packet, int length)=0
The function that writes bytes on the port buffer @description The function writes bytes on the port ...
virtual void setPortName(const char *port_name)=0
The function that sets port name into the port handler @description The function sets port name into ...
virtual void closePort()=0
The function that closes the port @description The function closes the port.
virtual void setPacketTimeout(double msec)=0
The function that sets and starts stopwatch for watching packet timeout @description The function set...
virtual void setPacketTimeout(uint16_t packet_length)=0
The function that sets and starts stopwatch for watching packet timeout @description The function set...
virtual int readPort(uint8_t *packet, int length)=0
The function that reads bytes from the port buffer @description The function gets bytes from the port...