port_handler_arduino.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * Copyright 2017 ROBOTIS CO., LTD.
00003 *
00004 * Licensed under the Apache License, Version 2.0 (the "License");
00005 * you may not use this file except in compliance with the License.
00006 * You may obtain a copy of the License at
00007 *
00008 *     http://www.apache.org/licenses/LICENSE-2.0
00009 *
00010 * Unless required by applicable law or agreed to in writing, software
00011 * distributed under the License is distributed on an "AS IS" BASIS,
00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013 * See the License for the specific language governing permissions and
00014 * limitations under the License.
00015 *******************************************************************************/
00016 
00021 
00022 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
00024 
00025 #if defined(ARDUINO) || defined(__OPENCR__) || defined (__OPENCM904__)
00026 #include <Arduino.h>
00027 #endif
00028 
00029 #include "port_handler.h"
00030 
00031 namespace dynamixel
00032 {
00033 
00037 class PortHandlerArduino : public PortHandler
00038 {
00039  private:
00040   int     socket_fd_;
00041   int     baudrate_;
00042   char    port_name_[100];
00043 
00044   double  packet_start_time_;
00045   double  packet_timeout_;
00046   double  tx_time_per_byte;
00047 
00048 #if defined(__OPENCM904__)
00049   UARTClass *p_dxl_serial;
00050 #endif
00051 
00052   bool    setupPort(const int cflag_baud);
00053 
00054   double  getCurrentTime();
00055   double  getTimeSinceStart();
00056 
00057   int     checkBaudrateAvailable(int baudrate);
00058 
00059   void    setPowerOn();
00060   void    setPowerOff();
00061   void    setTxEnable();
00062   void    setTxDisable();
00063 
00064  public:
00069   PortHandlerArduino(const char *port_name);
00070 
00075   virtual ~PortHandlerArduino() { closePort(); }
00076 
00082   bool    openPort();
00083 
00088   void    closePort();
00089 
00094   void    clearPort();
00095 
00101   void    setPortName(const char *port_name);
00102 
00108   char   *getPortName();
00109 
00118   bool    setBaudRate(const int baudrate);
00119 
00125   int     getBaudRate();
00126 
00133   int     getBytesAvailable();
00134 
00145   int     readPort(uint8_t *packet, int length);
00146 
00157   int     writePort(uint8_t *packet, int length);
00158 
00164   void    setPacketTimeout(uint16_t packet_length);
00165 
00171   void    setPacketTimeout(double msec);
00172 
00177   bool    isPacketTimeout();
00178 };
00179 
00180 }
00181 
00182 
00183 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ */


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11