19 #if defined(_WIN32) || defined(_WIN64) 28 #define LATENCY_TIMER 16 // msec (USB latency timer) 41 : serial_handle_(INVALID_HANDLE_VALUE),
42 baudrate_(DEFAULT_BAUDRATE_),
43 packet_start_time_(0.0),
45 tx_time_per_byte_(0.0)
50 sprintf_s(buffer,
sizeof(buffer),
"\\\\.\\%s", port_name);
61 if (serial_handle_ != INVALID_HANDLE_VALUE)
63 CloseHandle(serial_handle_);
64 serial_handle_ = INVALID_HANDLE_VALUE;
70 PurgeComm(serial_handle_, PURGE_RXABORT | PURGE_RXCLEAR);
99 BOOL res = DeviceIoControl(serial_handle_, GENERIC_READ | GENERIC_WRITE, NULL, 0, 0, 0, &retbyte, (LPOVERLAPPED)NULL);
101 printf(
"%d", (
int)res);
109 if (ReadFile(serial_handle_, packet, (DWORD)length, &dwRead, NULL) == FALSE)
119 if (WriteFile(serial_handle_, packet, (DWORD)length, &dwWrite, NULL) == FALSE)
149 QueryPerformanceCounter(&counter_);
150 QueryPerformanceFrequency(&freq_);
151 return (
double)counter_.QuadPart / (double)freq_.QuadPart * 1000.0;
167 COMMTIMEOUTS timeouts;
172 serial_handle_ = CreateFileA(
port_name_, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, NULL);
173 if (serial_handle_ == INVALID_HANDLE_VALUE)
175 printf(
"[PortHandlerWindows::SetupPort] Error opening serial port!\n");
179 dcb.DCBlength =
sizeof(DCB);
180 if (GetCommState(serial_handle_, &dcb) == FALSE)
181 goto DXL_HAL_OPEN_ERROR;
184 dcb.BaudRate = (DWORD)baudrate;
186 dcb.Parity = NOPARITY;
187 dcb.StopBits = ONESTOPBIT;
188 dcb.fParity = NOPARITY;
191 dcb.fAbortOnError = 0;
197 dcb.fDtrControl = DTR_CONTROL_DISABLE;
198 dcb.fRtsControl = RTS_CONTROL_DISABLE;
199 dcb.fDsrSensitivity = 0;
200 dcb.fOutxDsrFlow = 0;
201 dcb.fOutxCtsFlow = 0;
203 if (SetCommState(serial_handle_, &dcb) == FALSE)
204 goto DXL_HAL_OPEN_ERROR;
206 if (SetCommMask(serial_handle_, 0) == FALSE)
207 goto DXL_HAL_OPEN_ERROR;
208 if (SetupComm(serial_handle_, 4096, 4096) == FALSE)
209 goto DXL_HAL_OPEN_ERROR;
210 if (PurgeComm(serial_handle_, PURGE_TXABORT | PURGE_TXCLEAR | PURGE_RXABORT | PURGE_RXCLEAR) == FALSE)
211 goto DXL_HAL_OPEN_ERROR;
212 if (ClearCommError(serial_handle_, &dwError, NULL) == FALSE)
213 goto DXL_HAL_OPEN_ERROR;
215 if (GetCommTimeouts(serial_handle_, &timeouts) == FALSE)
216 goto DXL_HAL_OPEN_ERROR;
219 timeouts.ReadIntervalTimeout = 0;
220 timeouts.ReadTotalTimeoutMultiplier = 0;
221 timeouts.ReadTotalTimeoutConstant = 1;
222 timeouts.WriteTotalTimeoutMultiplier = 0;
223 timeouts.WriteTotalTimeoutConstant = 0;
224 if (SetCommTimeouts(serial_handle_, &timeouts) == FALSE)
225 goto DXL_HAL_OPEN_ERROR;
227 tx_time_per_byte_ = (1000.0 / (double)
baudrate_) * 10.0;
bool isPacketTimeout()
The function that checks whether packet timeout is occurred The function checks whether current time...
bool setupPort(const int baudrate)
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 setBaudRate(const int baudrate)
The function that sets baudrate into the port handler The function sets baudrate into the port handl...
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...
int readPort(uint8_t *packet, int length)
The function that reads bytes from the port buffer The function gets bytes from the port buffer...
bool setupPort(const int cflag_baud)
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer The function checks...
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler The function sets baudrate into the port handl...
int getBaudRate()
The function that returns current baudrate set into the port handler The function returns current ba...
double getTimeSinceStart()
char * getPortName()
The function that returns port name set into the port handler The function returns current port name...
void closePort()
The function that closes the port The function closes the port.
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout The function sets the stopwa...
void closePort()
The function that closes the port The function closes the port.
double packet_start_time_
bool openPort()
The function that opens the port The function calls PortHandlerWindows::setBaudRate() to open the po...
void clearPort()
The function that clears the port The function clears the port.
bool is_using_
shows whether the port is in use
double getTimeSinceStart()
PortHandlerWindows(const char *port_name)
The function that initializes instance of PortHandler and gets port_name The function initializes in...
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...