port_handler_windows.cpp
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 
17 /* Author: Ryu Woon Jung (Leon) */
18 
19 #if defined(_WIN32) || defined(_WIN64)
20 #define WINDLLEXPORT
21 
22 #include "port_handler_windows.h"
23 
24 #include <stdio.h>
25 #include <string.h>
26 #include <time.h>
27 
28 #define LATENCY_TIMER 16 // msec (USB latency timer)
29  // You should adjust the latency timer value. In Windows, the default latency timer of the usb serial is '16 msec'.
30  // When you are going to use sync / bulk read, the latency timer should be loosen.
31  // the lower latency timer value, the faster communication speed.
32 
33  // Note:
34  // You can either checking or changing its value by:
35  // [Device Manager] -> [Port (COM & LPT)] -> the port you use but starts with COMx-> mouse right click -> properties
36  // -> [port settings] -> [details] -> change response time from 16 to the value you need
37 
38 using namespace dynamixel;
39 
40 PortHandlerWindows::PortHandlerWindows(const char *port_name)
41  : serial_handle_(INVALID_HANDLE_VALUE),
42  baudrate_(DEFAULT_BAUDRATE_),
43  packet_start_time_(0.0),
44  packet_timeout_(0.0),
45  tx_time_per_byte_(0.0)
46 {
47  is_using_ = false;
48 
49  char buffer[15];
50  sprintf_s(buffer, sizeof(buffer), "\\\\.\\%s", port_name);
51  setPortName(buffer);
52 }
53 
55 {
56  return setBaudRate(baudrate_);
57 }
58 
60 {
61  if (serial_handle_ != INVALID_HANDLE_VALUE)
62  {
63  CloseHandle(serial_handle_);
64  serial_handle_ = INVALID_HANDLE_VALUE;
65  }
66 }
67 
69 {
70  PurgeComm(serial_handle_, PURGE_RXABORT | PURGE_RXCLEAR);
71 }
72 
73 void PortHandlerWindows::setPortName(const char *port_name)
74 {
75  strcpy_s(port_name_, sizeof(port_name_), port_name);
76 }
77 
79 {
80  return port_name_;
81 }
82 
83 bool PortHandlerWindows::setBaudRate(const int baudrate)
84 {
85  closePort();
86 
87  baudrate_ = baudrate;
88  return setupPort(baudrate);
89 }
90 
92 {
93  return baudrate_;
94 }
95 
97 {
98  DWORD retbyte = 2;
99  BOOL res = DeviceIoControl(serial_handle_, GENERIC_READ | GENERIC_WRITE, NULL, 0, 0, 0, &retbyte, (LPOVERLAPPED)NULL);
100 
101  printf("%d", (int)res);
102  return (int)retbyte;
103 }
104 
105 int PortHandlerWindows::readPort(uint8_t *packet, int length)
106 {
107  DWORD dwRead = 0;
108 
109  if (ReadFile(serial_handle_, packet, (DWORD)length, &dwRead, NULL) == FALSE)
110  return -1;
111 
112  return (int)dwRead;
113 }
114 
115 int PortHandlerWindows::writePort(uint8_t *packet, int length)
116 {
117  DWORD dwWrite = 0;
118 
119  if (WriteFile(serial_handle_, packet, (DWORD)length, &dwWrite, NULL) == FALSE)
120  return -1;
121 
122  return (int)dwWrite;
123 }
124 
125 void PortHandlerWindows::setPacketTimeout(uint16_t packet_length)
126 {
128  packet_timeout_ = (tx_time_per_byte_ * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
129 }
130 
131 void PortHandlerWindows::setPacketTimeout(double msec)
132 {
134  packet_timeout_ = msec;
135 }
136 
138 {
140  {
141  packet_timeout_ = 0;
142  return true;
143  }
144  return false;
145 }
146 
148 {
149  QueryPerformanceCounter(&counter_);
150  QueryPerformanceFrequency(&freq_);
151  return (double)counter_.QuadPart / (double)freq_.QuadPart * 1000.0;
152 }
153 
155 {
156  double time;
157 
159  if (time < 0.0) packet_start_time_ = getCurrentTime();
160 
161  return time;
162 }
163 
164 bool PortHandlerWindows::setupPort(int baudrate)
165 {
166  DCB dcb;
167  COMMTIMEOUTS timeouts;
168  DWORD dwError;
169 
170  closePort();
171 
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)
174  {
175  printf("[PortHandlerWindows::SetupPort] Error opening serial port!\n");
176  return false;
177  }
178 
179  dcb.DCBlength = sizeof(DCB);
180  if (GetCommState(serial_handle_, &dcb) == FALSE)
181  goto DXL_HAL_OPEN_ERROR;
182 
183  // Set baudrate
184  dcb.BaudRate = (DWORD)baudrate;
185  dcb.ByteSize = 8; // Data bit = 8bit
186  dcb.Parity = NOPARITY; // No parity
187  dcb.StopBits = ONESTOPBIT; // Stop bit = 1
188  dcb.fParity = NOPARITY; // No Parity check
189  dcb.fBinary = 1; // Binary mode
190  dcb.fNull = 0; // Get Null byte
191  dcb.fAbortOnError = 0;
192  dcb.fErrorChar = 0;
193  // Not using XOn/XOff
194  dcb.fOutX = 0;
195  dcb.fInX = 0;
196  // Not using H/W flow control
197  dcb.fDtrControl = DTR_CONTROL_DISABLE;
198  dcb.fRtsControl = RTS_CONTROL_DISABLE;
199  dcb.fDsrSensitivity = 0;
200  dcb.fOutxDsrFlow = 0;
201  dcb.fOutxCtsFlow = 0;
202 
203  if (SetCommState(serial_handle_, &dcb) == FALSE)
204  goto DXL_HAL_OPEN_ERROR;
205 
206  if (SetCommMask(serial_handle_, 0) == FALSE) // Not using Comm event
207  goto DXL_HAL_OPEN_ERROR;
208  if (SetupComm(serial_handle_, 4096, 4096) == FALSE) // Buffer size (Rx,Tx)
209  goto DXL_HAL_OPEN_ERROR;
210  if (PurgeComm(serial_handle_, PURGE_TXABORT | PURGE_TXCLEAR | PURGE_RXABORT | PURGE_RXCLEAR) == FALSE) // Clear buffer
211  goto DXL_HAL_OPEN_ERROR;
212  if (ClearCommError(serial_handle_, &dwError, NULL) == FALSE)
213  goto DXL_HAL_OPEN_ERROR;
214 
215  if (GetCommTimeouts(serial_handle_, &timeouts) == FALSE)
216  goto DXL_HAL_OPEN_ERROR;
217  // Timeout (Not using timeout)
218  // Immediatly return
219  timeouts.ReadIntervalTimeout = 0;
220  timeouts.ReadTotalTimeoutMultiplier = 0;
221  timeouts.ReadTotalTimeoutConstant = 1; // must not be zero.
222  timeouts.WriteTotalTimeoutMultiplier = 0;
223  timeouts.WriteTotalTimeoutConstant = 0;
224  if (SetCommTimeouts(serial_handle_, &timeouts) == FALSE)
225  goto DXL_HAL_OPEN_ERROR;
226 
227  tx_time_per_byte_ = (1000.0 / (double)baudrate_) * 10.0;
228  return true;
229 
230 DXL_HAL_OPEN_ERROR:
231  closePort();
232  return false;
233 }
234 
235 #endif
dynamixel::PortHandlerWindows::isPacketTimeout
bool isPacketTimeout()
The function that checks whether packet timeout is occurred @description The function checks whether ...
dynamixel::PortHandlerWindows::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 ...
port_handler_windows.h
dynamixel::PortHandlerWindows::port_name_
char port_name_[100]
Definition: port_handler_windows.h:42
dynamixel::PortHandlerWindows::closePort
void closePort()
The function that closes the port @description The function closes the port.
time.h
dynamixel::PortHandler::is_using_
bool is_using_
shows whether the port is in use
Definition: port_handler.h:67
dynamixel::PortHandlerMac::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::PortHandlerWindows::packet_timeout_
double packet_timeout_
Definition: port_handler_windows.h:45
dynamixel::PortHandlerWindows::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::PortHandlerWindows::setupPort
bool setupPort(const int baudrate)
dynamixel::PortHandlerWindows::getTimeSinceStart
double getTimeSinceStart()
dynamixel::PortHandlerWindows::packet_start_time_
double packet_start_time_
Definition: port_handler_windows.h:44
dynamixel
Definition: group_bulk_read.h:31
dynamixel::PortHandlerWindows::baudrate_
int baudrate_
Definition: port_handler_windows.h:41
dynamixel::PortHandlerWindows::getBytesAvailable
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer @description The fun...
dynamixel::PortHandlerWindows::freq_
LARGE_INTEGER freq_
Definition: port_handler_windows.h:39
dynamixel::PortHandlerWindows::getBaudRate
int getBaudRate()
The function that returns current baudrate set into the port handler @description The function return...
dynamixel::PortHandlerWindows::getCurrentTime
double getCurrentTime()
dynamixel::PortHandlerWindows::getPortName
char * getPortName()
The function that returns port name set into the port handler @description The function returns curre...
dynamixel::PortHandlerWindows::serial_handle_
HANDLE serial_handle_
Definition: port_handler_windows.h:38
dynamixel::PortHandlerWindows::clearPort
void clearPort()
The function that clears the port @description The function clears the port.
dynamixel::PortHandlerWindows::tx_time_per_byte_
double tx_time_per_byte_
Definition: port_handler_windows.h:46
dynamixel::PortHandlerWindows::setBaudRate
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler @description The function sets baudrate into th...
dynamixel::PortHandlerWindows::counter_
LARGE_INTEGER counter_
Definition: port_handler_windows.h:39
dynamixel::PortHandlerWindows::PortHandlerWindows
PortHandlerWindows(const char *port_name)
The function that initializes instance of PortHandler and gets port_name @description The function in...
dynamixel::PortHandlerWindows::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::PortHandlerWindows::setPacketTimeout
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout @description The function set...
dynamixel::PortHandlerWindows::openPort
bool openPort()
The function that opens the port @description The function calls PortHandlerWindows::setBaudRate() to...
dynamixel_sdk.port_handler.LATENCY_TIMER
int LATENCY_TIMER
Definition: port_handler.py:27


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