port_handler_arduino.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
21 
22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
24 
25 #if defined(ARDUINO) || defined(__OPENCR__) || defined (__OPENCM904__)
26 #include <Arduino.h>
27 #endif
28 
29 #include "port_handler.h"
30 
31 namespace dynamixel
32 {
33 
38 {
39  private:
41  int baudrate_;
42  char port_name_[100];
43 
47 
48 #if defined(__OPENCM904__)
49  UARTClass *p_dxl_serial;
50 #endif
51 
52  bool setupPort(const int cflag_baud);
53 
54  double getCurrentTime();
55  double getTimeSinceStart();
56 
57  int checkBaudrateAvailable(int baudrate);
58 
59  void setPowerOn();
60  void setPowerOff();
61  void setTxEnable();
62  void setTxDisable();
63 
64  public:
69  PortHandlerArduino(const char *port_name);
70 
75  virtual ~PortHandlerArduino() { closePort(); }
76 
82  bool openPort();
83 
88  void closePort();
89 
94  void clearPort();
95 
101  void setPortName(const char *port_name);
102 
108  char *getPortName();
109 
118  bool setBaudRate(const int baudrate);
119 
125  int getBaudRate();
126 
133  int getBytesAvailable();
134 
145  int readPort(uint8_t *packet, int length);
146 
157  int writePort(uint8_t *packet, int length);
158 
164  void setPacketTimeout(uint16_t packet_length);
165 
171  void setPacketTimeout(double msec);
172 
177  bool isPacketTimeout();
178 };
179 
180 }
181 
182 
183 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ */
int writePort(uint8_t *packet, int length)
The function that writes bytes on the port buffer The function writes bytes on the port buffer...
bool setupPort(const int cflag_baud)
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout The function sets the stopwa...
int checkBaudrateAvailable(int baudrate)
int readPort(uint8_t *packet, int length)
The function that reads bytes from the port buffer The function gets bytes from the port buffer...
int getBaudRate()
The function that returns current baudrate set into the port handler The function returns current ba...
void closePort()
The function that closes the port The function closes the port.
The class for control port in Arduino.
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler The function sets baudrate into the port handl...
PortHandlerArduino(const char *port_name)
The function that initializes instance of PortHandler and gets port_name The function initializes in...
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56
bool openPort()
The function that opens the port The function calls PortHandlerArduino::setBaudRate() to open the po...
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer The function checks...
virtual ~PortHandlerArduino()
The function that closes the port The function calls PortHandlerArduino::closePort() to close the po...
void clearPort()
The function that clears the port The function clears the port.
char * getPortName()
The function that returns port name set into the port handler The function returns current port name...
void setPortName(const char *port_name)
The function that sets port name into the port handler The function sets port name into the port han...
bool isPacketTimeout()
The function that checks whether packet timeout is occurred The function checks whether current time...


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55