Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00021
00022 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_
00024
00025 #include <Windows.h>
00026
00027 #include "port_handler.h"
00028
00029 namespace dynamixel
00030 {
00031
00035 class WINDECLSPEC PortHandlerWindows : public PortHandler
00036 {
00037 private:
00038 HANDLE serial_handle_;
00039 LARGE_INTEGER freq_, counter_;
00040
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 bool setupPort(const int baudrate);
00049
00050 double getCurrentTime();
00051 double getTimeSinceStart();
00052
00053 public:
00058 PortHandlerWindows(const char *port_name);
00059
00064 virtual ~PortHandlerWindows() { closePort(); }
00065
00071 bool openPort();
00072
00077 void closePort();
00078
00083 void clearPort();
00084
00090 void setPortName(const char *port_name);
00091
00097 char *getPortName();
00098
00107 bool setBaudRate(const int baudrate);
00108
00114 int getBaudRate();
00115
00122 int getBytesAvailable();
00123
00134 int readPort(uint8_t *packet, int length);
00135
00146 int writePort(uint8_t *packet, int length);
00147
00153 void setPacketTimeout(uint16_t packet_length);
00154
00160 void setPacketTimeout(double msec);
00161
00166 bool isPacketTimeout();
00167 };
00168
00169 }
00170
00171
00172 #endif