Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #if defined(_WIN32) || defined(_WIN64)
00020 #define WINDLLEXPORT
00021
00022 #include "port_handler_windows.h"
00023
00024 #include <stdio.h>
00025 #include <string.h>
00026 #include <time.h>
00027
00028 #define LATENCY_TIMER 16 // msec (USB latency timer)
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 using namespace dynamixel;
00039
00040 PortHandlerWindows::PortHandlerWindows(const char *port_name)
00041 : serial_handle_(INVALID_HANDLE_VALUE),
00042 baudrate_(DEFAULT_BAUDRATE_),
00043 packet_start_time_(0.0),
00044 packet_timeout_(0.0),
00045 tx_time_per_byte_(0.0)
00046 {
00047 is_using_ = false;
00048
00049 char buffer[15];
00050 sprintf_s(buffer, sizeof(buffer), "\\\\.\\%s", port_name);
00051 setPortName(buffer);
00052 }
00053
00054 bool PortHandlerWindows::openPort()
00055 {
00056 return setBaudRate(baudrate_);
00057 }
00058
00059 void PortHandlerWindows::closePort()
00060 {
00061 if (serial_handle_ != INVALID_HANDLE_VALUE)
00062 {
00063 CloseHandle(serial_handle_);
00064 serial_handle_ = INVALID_HANDLE_VALUE;
00065 }
00066 }
00067
00068 void PortHandlerWindows::clearPort()
00069 {
00070 PurgeComm(serial_handle_, PURGE_RXABORT | PURGE_RXCLEAR);
00071 }
00072
00073 void PortHandlerWindows::setPortName(const char *port_name)
00074 {
00075 strcpy_s(port_name_, sizeof(port_name_), port_name);
00076 }
00077
00078 char *PortHandlerWindows::getPortName()
00079 {
00080 return port_name_;
00081 }
00082
00083 bool PortHandlerWindows::setBaudRate(const int baudrate)
00084 {
00085 closePort();
00086
00087 baudrate_ = baudrate;
00088 return setupPort(baudrate);
00089 }
00090
00091 int PortHandlerWindows::getBaudRate()
00092 {
00093 return baudrate_;
00094 }
00095
00096 int PortHandlerWindows::getBytesAvailable()
00097 {
00098 DWORD retbyte = 2;
00099 BOOL res = DeviceIoControl(serial_handle_, GENERIC_READ | GENERIC_WRITE, NULL, 0, 0, 0, &retbyte, (LPOVERLAPPED)NULL);
00100
00101 printf("%d", (int)res);
00102 return (int)retbyte;
00103 }
00104
00105 int PortHandlerWindows::readPort(uint8_t *packet, int length)
00106 {
00107 DWORD dwRead = 0;
00108
00109 if (ReadFile(serial_handle_, packet, (DWORD)length, &dwRead, NULL) == FALSE)
00110 return -1;
00111
00112 return (int)dwRead;
00113 }
00114
00115 int PortHandlerWindows::writePort(uint8_t *packet, int length)
00116 {
00117 DWORD dwWrite = 0;
00118
00119 if (WriteFile(serial_handle_, packet, (DWORD)length, &dwWrite, NULL) == FALSE)
00120 return -1;
00121
00122 return (int)dwWrite;
00123 }
00124
00125 void PortHandlerWindows::setPacketTimeout(uint16_t packet_length)
00126 {
00127 packet_start_time_ = getCurrentTime();
00128 packet_timeout_ = (tx_time_per_byte_ * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
00129 }
00130
00131 void PortHandlerWindows::setPacketTimeout(double msec)
00132 {
00133 packet_start_time_ = getCurrentTime();
00134 packet_timeout_ = msec;
00135 }
00136
00137 bool PortHandlerWindows::isPacketTimeout()
00138 {
00139 if (getTimeSinceStart() > packet_timeout_)
00140 {
00141 packet_timeout_ = 0;
00142 return true;
00143 }
00144 return false;
00145 }
00146
00147 double PortHandlerWindows::getCurrentTime()
00148 {
00149 QueryPerformanceCounter(&counter_);
00150 QueryPerformanceFrequency(&freq_);
00151 return (double)counter_.QuadPart / (double)freq_.QuadPart * 1000.0;
00152 }
00153
00154 double PortHandlerWindows::getTimeSinceStart()
00155 {
00156 double time;
00157
00158 time = getCurrentTime() - packet_start_time_;
00159 if (time < 0.0) packet_start_time_ = getCurrentTime();
00160
00161 return time;
00162 }
00163
00164 bool PortHandlerWindows::setupPort(int baudrate)
00165 {
00166 DCB dcb;
00167 COMMTIMEOUTS timeouts;
00168 DWORD dwError;
00169
00170 closePort();
00171
00172 serial_handle_ = CreateFileA(port_name_, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, NULL);
00173 if (serial_handle_ == INVALID_HANDLE_VALUE)
00174 {
00175 printf("[PortHandlerWindows::SetupPort] Error opening serial port!\n");
00176 return false;
00177 }
00178
00179 dcb.DCBlength = sizeof(DCB);
00180 if (GetCommState(serial_handle_, &dcb) == FALSE)
00181 goto DXL_HAL_OPEN_ERROR;
00182
00183
00184 dcb.BaudRate = (DWORD)baudrate;
00185 dcb.ByteSize = 8;
00186 dcb.Parity = NOPARITY;
00187 dcb.StopBits = ONESTOPBIT;
00188 dcb.fParity = NOPARITY;
00189 dcb.fBinary = 1;
00190 dcb.fNull = 0;
00191 dcb.fAbortOnError = 0;
00192 dcb.fErrorChar = 0;
00193
00194 dcb.fOutX = 0;
00195 dcb.fInX = 0;
00196
00197 dcb.fDtrControl = DTR_CONTROL_DISABLE;
00198 dcb.fRtsControl = RTS_CONTROL_DISABLE;
00199 dcb.fDsrSensitivity = 0;
00200 dcb.fOutxDsrFlow = 0;
00201 dcb.fOutxCtsFlow = 0;
00202
00203 if (SetCommState(serial_handle_, &dcb) == FALSE)
00204 goto DXL_HAL_OPEN_ERROR;
00205
00206 if (SetCommMask(serial_handle_, 0) == FALSE)
00207 goto DXL_HAL_OPEN_ERROR;
00208 if (SetupComm(serial_handle_, 4096, 4096) == FALSE)
00209 goto DXL_HAL_OPEN_ERROR;
00210 if (PurgeComm(serial_handle_, PURGE_TXABORT | PURGE_TXCLEAR | PURGE_RXABORT | PURGE_RXCLEAR) == FALSE)
00211 goto DXL_HAL_OPEN_ERROR;
00212 if (ClearCommError(serial_handle_, &dwError, NULL) == FALSE)
00213 goto DXL_HAL_OPEN_ERROR;
00214
00215 if (GetCommTimeouts(serial_handle_, &timeouts) == FALSE)
00216 goto DXL_HAL_OPEN_ERROR;
00217
00218
00219 timeouts.ReadIntervalTimeout = 0;
00220 timeouts.ReadTotalTimeoutMultiplier = 0;
00221 timeouts.ReadTotalTimeoutConstant = 1;
00222 timeouts.WriteTotalTimeoutMultiplier = 0;
00223 timeouts.WriteTotalTimeoutConstant = 0;
00224 if (SetCommTimeouts(serial_handle_, &timeouts) == FALSE)
00225 goto DXL_HAL_OPEN_ERROR;
00226
00227 tx_time_per_byte_ = (1000.0 / (double)baudrate_) * 10.0;
00228 return true;
00229
00230 DXL_HAL_OPEN_ERROR:
00231 closePort();
00232 return false;
00233 }
00234
00235 #endif