port_handler_linux.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: zerom, Ryu Woon Jung (Leon) */
18 
19 #if defined(__linux__)
20 
21 #include <stdio.h>
22 #include <fcntl.h>
23 #include <string.h>
24 #include <unistd.h>
25 #include <termios.h>
26 #include <time.h>
27 #include <sys/time.h>
28 #include <sys/ioctl.h>
29 #include <linux/serial.h>
30 
31 #include "port_handler_linux.h"
32 
33 #define LATENCY_TIMER 16 // msec (USB latency timer)
34  // You should adjust the latency timer value. From the version Ubuntu 16.04.2, the default latency timer of the usb serial is '16 msec'.
35  // When you are going to use sync / bulk read, the latency timer should be loosen.
36  // the lower latency timer value, the faster communication speed.
37 
38  // Note:
39  // You can check its value by:
40  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
41  //
42  // If you think that the communication is too slow, type following after plugging the usb in to change the latency timer
43  //
44  // Method 1. Type following (you should do this everytime when the usb once was plugged out or the connection was dropped)
45  // $ echo 1 | sudo tee /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
46  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
47  //
48  // Method 2. If you want to set it as be done automatically, and don't want to do above everytime, make rules file in /etc/udev/rules.d/. For example,
49  // $ echo ACTION==\"add\", SUBSYSTEM==\"usb-serial\", DRIVER==\"ftdi_sio\", ATTR{latency_timer}=\"1\" > 99-dynamixelsdk-usb.rules
50  // $ sudo cp ./99-dynamixelsdk-usb.rules /etc/udev/rules.d/
51  // $ sudo udevadm control --reload-rules
52  // $ sudo udevadm trigger --action=add
53  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
54  //
55  // or if you have another good idea that can be an alternatives,
56  // please give us advice via github issue https://github.com/ROBOTIS-GIT/DynamixelSDK/issues
57 
58 struct termios2 {
59  tcflag_t c_iflag; /* input mode flags */
60  tcflag_t c_oflag; /* output mode flags */
61  tcflag_t c_cflag; /* control mode flags */
62  tcflag_t c_lflag; /* local mode flags */
63  cc_t c_line; /* line discipline */
64  cc_t c_cc[19]; /* control characters */
65  speed_t c_ispeed; /* input speed */
66  speed_t c_ospeed; /* output speed */
67 };
68 
69 #ifndef TCGETS2
70 #define TCGETS2 _IOR('T', 0x2A, struct termios2)
71 #endif
72 #ifndef TCSETS2
73 #define TCSETS2 _IOW('T', 0x2B, struct termios2)
74 #endif
75 #ifndef BOTHER
76 #define BOTHER 0010000
77 #endif
78 
79 using namespace dynamixel;
80 
81 PortHandlerLinux::PortHandlerLinux(const char *port_name)
82  : socket_fd_(-1),
83  baudrate_(DEFAULT_BAUDRATE_),
84  packet_start_time_(0.0),
85  packet_timeout_(0.0),
86  tx_time_per_byte(0.0)
87 {
88  is_using_ = false;
89  setPortName(port_name);
90 }
91 
93 {
94  return setBaudRate(baudrate_);
95 }
96 
98 {
99  if(socket_fd_ != -1)
100  close(socket_fd_);
101  socket_fd_ = -1;
102 }
103 
105 {
106  tcflush(socket_fd_, TCIFLUSH);
107 }
108 
109 void PortHandlerLinux::setPortName(const char *port_name)
110 {
111  strcpy(port_name_, port_name);
112 }
113 
115 {
116  return port_name_;
117 }
118 
119 // TODO: baud number ??
120 bool PortHandlerLinux::setBaudRate(const int baudrate)
121 {
122  int baud = getCFlagBaud(baudrate);
123 
124  closePort();
125 
126  if(baud <= 0) // custom baudrate
127  {
128  setupPort(B38400);
129  baudrate_ = baudrate;
130  return setCustomBaudrate(baudrate);
131  }
132  else
133  {
134  baudrate_ = baudrate;
135  return setupPort(baud);
136  }
137 }
138 
140 {
141  return baudrate_;
142 }
143 
145 {
146  int bytes_available;
147  ioctl(socket_fd_, FIONREAD, &bytes_available);
148  return bytes_available;
149 }
150 
151 int PortHandlerLinux::readPort(uint8_t *packet, int length)
152 {
153  return read(socket_fd_, packet, length);
154 }
155 
156 int PortHandlerLinux::writePort(uint8_t *packet, int length)
157 {
158  return write(socket_fd_, packet, length);
159 }
160 
161 void PortHandlerLinux::setPacketTimeout(uint16_t packet_length)
162 {
164  packet_timeout_ = (tx_time_per_byte * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
165 }
166 
167 void PortHandlerLinux::setPacketTimeout(double msec)
168 {
170  packet_timeout_ = msec;
171 }
172 
174 {
176  {
177  packet_timeout_ = 0;
178  return true;
179  }
180  return false;
181 }
182 
184 {
185  struct timespec tv;
186  clock_gettime(CLOCK_REALTIME, &tv);
187  return ((double)tv.tv_sec * 1000.0 + (double)tv.tv_nsec * 0.001 * 0.001);
188 }
189 
191 {
192  double time;
193 
195  if(time < 0.0)
197 
198  return time;
199 }
200 
201 bool PortHandlerLinux::setupPort(int cflag_baud)
202 {
203  struct termios newtio;
204 
205  socket_fd_ = open(port_name_, O_RDWR|O_NOCTTY|O_NONBLOCK);
206  if(socket_fd_ < 0)
207  {
208  printf("[PortHandlerLinux::SetupPort] Error opening serial port!\n");
209  return false;
210  }
211 
212  bzero(&newtio, sizeof(newtio)); // clear struct for new port settings
213 
214  newtio.c_cflag = cflag_baud | CS8 | CLOCAL | CREAD;
215  newtio.c_iflag = IGNPAR;
216  newtio.c_oflag = 0;
217  newtio.c_lflag = 0;
218  newtio.c_cc[VTIME] = 0;
219  newtio.c_cc[VMIN] = 0;
220 
221  // clean the buffer and activate the settings for the port
222  tcflush(socket_fd_, TCIFLUSH);
223  tcsetattr(socket_fd_, TCSANOW, &newtio);
224 
225  tx_time_per_byte = (1000.0 / (double)baudrate_) * 10.0;
226  return true;
227 }
228 
230 {
231  struct termios2 options;
232 
233  if (ioctl(socket_fd_, TCGETS2, &options) != 01)
234  {
235  options.c_cflag &= ~CBAUD;
236  options.c_cflag |= BOTHER;
237  options.c_ispeed = speed;
238  options.c_ospeed = speed;
239 
240  if (ioctl(socket_fd_, TCSETS2, &options) != -1)
241  return true;
242  }
243 
244  // try to set a custom divisor
245  struct serial_struct ss;
246  if(ioctl(socket_fd_, TIOCGSERIAL, &ss) != 0)
247  {
248  printf("[PortHandlerLinux::SetCustomBaudrate] TIOCGSERIAL failed!\n");
249  return false;
250  }
251 
252  ss.flags = (ss.flags & ~ASYNC_SPD_MASK) | ASYNC_SPD_CUST;
253  ss.custom_divisor = (ss.baud_base + (speed / 2)) / speed;
254  int closest_speed = ss.baud_base / ss.custom_divisor;
255 
256  if(closest_speed < speed * 98 / 100 || closest_speed > speed * 102 / 100)
257  {
258  printf("[PortHandlerLinux::SetCustomBaudrate] Cannot set speed to %d, closest is %d \n", speed, closest_speed);
259  return false;
260  }
261 
262  if(ioctl(socket_fd_, TIOCSSERIAL, &ss) < 0)
263  {
264  printf("[PortHandlerLinux::SetCustomBaudrate] TIOCSSERIAL failed!\n");
265  return false;
266  }
267 
268  tx_time_per_byte = (1000.0 / (double)speed) * 10.0;
269  return true;
270 }
271 
272 int PortHandlerLinux::getCFlagBaud(int baudrate)
273 {
274  switch(baudrate)
275  {
276  case 9600:
277  return B9600;
278  case 19200:
279  return B19200;
280  case 38400:
281  return B38400;
282  case 57600:
283  return B57600;
284  case 115200:
285  return B115200;
286  case 230400:
287  return B230400;
288  case 460800:
289  return B460800;
290  case 500000:
291  return B500000;
292  case 576000:
293  return B576000;
294  case 921600:
295  return B921600;
296  case 1000000:
297  return B1000000;
298  case 1152000:
299  return B1152000;
300  case 1500000:
301  return B1500000;
302  case 2000000:
303  return B2000000;
304  case 2500000:
305  return B2500000;
306  case 3000000:
307  return B3000000;
308  case 3500000:
309  return B3500000;
310  case 4000000:
311  return B4000000;
312  default:
313  return -1;
314  }
315 }
316 
317 #endif
port_handler_linux.h
dynamixel::PortHandlerLinux::isPacketTimeout
bool isPacketTimeout()
The function that checks whether packet timeout is occurred @description The function checks whether ...
dynamixel::PortHandlerLinux::tx_time_per_byte
double tx_time_per_byte
Definition: port_handler_linux.h:43
dynamixel::PortHandlerLinux::setCustomBaudrate
bool setCustomBaudrate(int speed)
dynamixel::PortHandlerLinux::getPortName
char * getPortName()
The function that returns port name set into the port handler @description The function returns curre...
dynamixel::PortHandlerLinux::setupPort
bool setupPort(const int cflag_baud)
dynamixel::PortHandlerLinux::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 ...
dynamixel::PortHandlerLinux::setPacketTimeout
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout @description The function set...
dynamixel::PortHandlerLinux::packet_start_time_
double packet_start_time_
Definition: port_handler_linux.h:41
time.h
dynamixel::PortHandlerLinux::setBaudRate
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler @description The function sets baudrate into th...
dynamixel::PortHandler::is_using_
bool is_using_
shows whether the port is in use
Definition: port_handler.h:67
dynamixel::PortHandlerArduino::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::PortHandlerLinux::closePort
void closePort()
The function that closes the port @description The function closes the port.
dynamixel
Definition: group_bulk_read.h:31
dynamixel::PortHandlerLinux::PortHandlerLinux
PortHandlerLinux(const char *port_name)
The function that initializes instance of PortHandler and gets port_name @description The function in...
dynamixel::PortHandlerLinux::getCurrentTime
double getCurrentTime()
dynamixel::PortHandlerLinux::getCFlagBaud
int getCFlagBaud(const int baudrate)
dynamixel::PortHandlerLinux::socket_fd_
int socket_fd_
Definition: port_handler_linux.h:37
dynamixel::PortHandlerLinux::baudrate_
int baudrate_
Definition: port_handler_linux.h:38
dynamixel::PortHandlerLinux::getBytesAvailable
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer @description The fun...
dynamixel::PortHandlerLinux::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::PortHandlerLinux::packet_timeout_
double packet_timeout_
Definition: port_handler_linux.h:42
dynamixel::PortHandlerLinux::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::PortHandlerLinux::getBaudRate
int getBaudRate()
The function that returns current baudrate set into the port handler @description The function return...
dynamixel::PortHandlerLinux::getTimeSinceStart
double getTimeSinceStart()
dynamixel::PortHandlerLinux::port_name_
char port_name_[100]
Definition: port_handler_linux.h:39
dynamixel_sdk.port_handler.LATENCY_TIMER
int LATENCY_TIMER
Definition: port_handler.py:27
dynamixel::PortHandlerLinux::clearPort
void clearPort()
The function that clears the port @description The function clears the port.
dynamixel::PortHandlerLinux::openPort
bool openPort()
The function that opens the port @description The function calls PortHandlerLinux::setBaudRate() to o...


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