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_ */
dynamixel::PortHandlerArduino::isPacketTimeout
bool isPacketTimeout()
The function that checks whether packet timeout is occurred @description The function checks whether ...
dynamixel::PortHandlerArduino::setPacketTimeout
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout @description The function set...
dynamixel::PortHandlerArduino::getCurrentTime
double getCurrentTime()
dynamixel::PortHandlerArduino::baudrate_
int baudrate_
Definition: port_handler_arduino.h:41
dynamixel::PortHandlerArduino::setTxEnable
void setTxEnable()
dynamixel::PortHandlerArduino::tx_time_per_byte
double tx_time_per_byte
Definition: port_handler_arduino.h:46
dynamixel::PortHandlerArduino::~PortHandlerArduino
virtual ~PortHandlerArduino()
The function that closes the port @description The function calls PortHandlerArduino::closePort() to ...
Definition: port_handler_arduino.h:75
dynamixel::PortHandlerArduino::openPort
bool openPort()
The function that opens the port @description The function calls PortHandlerArduino::setBaudRate() to...
dynamixel::PortHandlerArduino::getBaudRate
int getBaudRate()
The function that returns current baudrate set into the port handler @description The function return...
dynamixel::PortHandlerArduino::getPortName
char * getPortName()
The function that returns port name set into the port handler @description The function returns curre...
dynamixel::PortHandlerArduino::setPortName
void setPortName(const char *port_name)
The function that sets port name into the port handler @description The function sets port name into ...
dynamixel::PortHandlerArduino::getTimeSinceStart
double getTimeSinceStart()
dynamixel::PortHandlerArduino::closePort
void closePort()
The function that closes the port @description The function closes the port.
dynamixel::PortHandlerArduino::setupPort
bool setupPort(const int cflag_baud)
dynamixel::PortHandlerArduino::checkBaudrateAvailable
int checkBaudrateAvailable(int baudrate)
dynamixel::PortHandlerArduino::clearPort
void clearPort()
The function that clears the port @description The function clears the port.
dynamixel
Definition: group_bulk_read.h:31
dynamixel::PortHandler
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition: port_handler.h:56
dynamixel::PortHandlerArduino::readPort
int readPort(uint8_t *packet, int length)
The function that reads bytes from the port buffer @description The function gets bytes from the port...
dynamixel::PortHandlerArduino::PortHandlerArduino
PortHandlerArduino(const char *port_name)
The function that initializes instance of PortHandler and gets port_name @description The function in...
dynamixel::PortHandlerArduino::setTxDisable
void setTxDisable()
dynamixel::PortHandlerArduino::getBytesAvailable
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer @description The fun...
dynamixel::PortHandlerArduino::setBaudRate
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler @description The function sets baudrate into th...
dynamixel::PortHandlerArduino::socket_fd_
int socket_fd_
Definition: port_handler_arduino.h:40
dynamixel::PortHandlerArduino::writePort
int writePort(uint8_t *packet, int length)
The function that writes bytes on the port buffer @description The function writes bytes on the port ...
dynamixel::PortHandlerArduino
The class for control port in Arduino.
Definition: port_handler_arduino.h:37
dynamixel::PortHandlerArduino::packet_start_time_
double packet_start_time_
Definition: port_handler_arduino.h:44
dynamixel::PortHandlerArduino::port_name_
char port_name_[100]
Definition: port_handler_arduino.h:42
dynamixel::PortHandlerArduino::setPowerOn
void setPowerOn()
dynamixel::PortHandlerArduino::packet_timeout_
double packet_timeout_
Definition: port_handler_arduino.h:45
port_handler.h
dynamixel::PortHandlerArduino::setPowerOff
void setPowerOff()


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Wed Mar 2 2022 00:13:50