MercurySDK
Software development kit for Mercury digital servos
port_handler_linux.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (C) 2021 <Robot Articulation/code@robotarticulation.com>
3 *
4 * Source files modified to support the Mercury range of digital servo motors from Robot Articulation
5 *******************************************************************************/
6 
7 /*******************************************************************************
8 * Copyright 2017 ROBOTIS CO., LTD.
9 *
10 * Licensed under the Apache License, Version 2.0 (the "License");
11 * you may not use this file except in compliance with the License.
12 * You may obtain a copy of the License at
13 *
14 * http://www.apache.org/licenses/LICENSE-2.0
15 *
16 * Unless required by applicable law or agreed to in writing, software
17 * distributed under the License is distributed on an "AS IS" BASIS,
18 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19 * See the License for the specific language governing permissions and
20 * limitations under the License.
21 *******************************************************************************/
22 
23 /* Original author: Zerom, Leon (RyuWoon Jung) */
24 
25 #if defined(__linux__)
26 
27 #include <stdio.h>
28 #include <fcntl.h>
29 #include <string.h>
30 #include <unistd.h>
31 #include <termios.h>
32 #include <time.h>
33 #include <sys/time.h>
34 #include <sys/ioctl.h>
35 #include <linux/serial.h>
36 
37 #include "port_handler_linux.h"
38 
39 #define LATENCY_TIMER 16 // msec (USB latency timer)
40  // 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'.
41  // When you are going to use sync / bulk read, the latency timer should be loosen.
42  // the lower latency timer value, the faster communication speed.
43 
44  // Note:
45  // You can check its value by:
46  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
47  //
48  // If you think that the communication is too slow, type following after plugging the usb in to change the latency timer
49  //
50  // Method 1. Type following (you should do this everytime when the usb once was plugged out or the connection was dropped)
51  // $ echo 1 | sudo tee /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
52  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
53  //
54  // 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,
55  // $ echo ACTION==\"add\", SUBSYSTEM==\"usb-serial\", DRIVER==\"ftdi_sio\", ATTR{latency_timer}=\"1\" > 99-mercurysdk-usb.rules
56  // $ sudo cp ./99-mercurysdk-usb.rules /etc/udev/rules.d/
57  // $ sudo udevadm control --reload-rules
58  // $ sudo udevadm trigger --action=add
59  // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
60 
61 using namespace mercury;
62 
63 PortHandlerLinux::PortHandlerLinux(const char *port_name)
64  : socket_fd_(-1),
65  baudrate_(DEFAULT_BAUDRATE_),
66  packet_start_time_(0.0),
67  packet_timeout_(0.0),
68  tx_time_per_byte(0.0)
69 {
70  is_using_ = false;
71  setPortName(port_name);
72 }
73 
74 bool PortHandlerLinux::openPort()
75 {
76  return setBaudRate(baudrate_);
77 }
78 
80 {
81  if(socket_fd_ != -1)
82  close(socket_fd_);
83  socket_fd_ = -1;
84 }
85 
87 {
88  tcflush(socket_fd_, TCIFLUSH);
89 }
90 
91 void PortHandlerLinux::setPortName(const char *port_name)
92 {
93  strcpy(port_name_, port_name);
94 }
95 
97 {
98  return port_name_;
99 }
100 
101 // TODO: baud number ??
102 bool PortHandlerLinux::setBaudRate(const int baudrate)
103 {
104  int baud = getCFlagBaud(baudrate);
105 
106  closePort();
107 
108  if(baud <= 0) // custom baudrate
109  {
110  setupPort(B38400);
111  baudrate_ = baudrate;
112  return setCustomBaudrate(baudrate);
113  }
114  else
115  {
116  baudrate_ = baudrate;
117  return setupPort(baud);
118  }
119 }
120 
122 {
123  return baudrate_;
124 }
125 
127 {
128  int bytes_available;
129  ioctl(socket_fd_, FIONREAD, &bytes_available);
130  return bytes_available;
131 }
132 
133 int PortHandlerLinux::readPort(uint8_t *packet, int length)
134 {
135  return read(socket_fd_, packet, length);
136 }
137 
138 int PortHandlerLinux::writePort(uint8_t *packet, int length)
139 {
140  return write(socket_fd_, packet, length);
141 }
142 
143 void PortHandlerLinux::setPacketTimeout(uint16_t packet_length)
144 {
145  packet_start_time_ = getCurrentTime();
146  packet_timeout_ = (tx_time_per_byte * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
147 }
148 
149 void PortHandlerLinux::setPacketTimeout(double msec)
150 {
151  packet_start_time_ = getCurrentTime();
152  packet_timeout_ = msec;
153 }
154 
156 {
157  if(getTimeSinceStart() > packet_timeout_)
158  {
159  packet_timeout_ = 0;
160  return true;
161  }
162  return false;
163 }
164 
165 double PortHandlerLinux::getCurrentTime()
166 {
167  struct timespec tv;
168  clock_gettime(CLOCK_REALTIME, &tv);
169  return ((double)tv.tv_sec * 1000.0 + (double)tv.tv_nsec * 0.001 * 0.001);
170 }
171 
172 double PortHandlerLinux::getTimeSinceStart()
173 {
174  double time;
175 
176  time = getCurrentTime() - packet_start_time_;
177  if(time < 0.0)
178  packet_start_time_ = getCurrentTime();
179 
180  return time;
181 }
182 
183 bool PortHandlerLinux::setupPort(int cflag_baud)
184 {
185  struct termios newtio;
186 
187  socket_fd_ = open(port_name_, O_RDWR|O_NOCTTY|O_NONBLOCK);
188  if(socket_fd_ < 0)
189  {
190  printf("[PortHandlerLinux::SetupPort] Error opening serial port!\n");
191  return false;
192  }
193 
194  bzero(&newtio, sizeof(newtio)); // clear struct for new port settings
195 
196  newtio.c_cflag = cflag_baud | CS8 | CLOCAL | CREAD;
197  newtio.c_iflag = IGNPAR;
198  newtio.c_oflag = 0;
199  newtio.c_lflag = 0;
200  newtio.c_cc[VTIME] = 0;
201  newtio.c_cc[VMIN] = 0;
202 
203  // clean the buffer and activate the settings for the port
204  tcflush(socket_fd_, TCIFLUSH);
205  tcsetattr(socket_fd_, TCSANOW, &newtio);
206 
207  tx_time_per_byte = (1000.0 / (double)baudrate_) * 10.0;
208  return true;
209 }
210 
211 bool PortHandlerLinux::setCustomBaudrate(int speed)
212 {
213  // try to set a custom divisor
214  struct serial_struct ss;
215  if(ioctl(socket_fd_, TIOCGSERIAL, &ss) != 0)
216  {
217  printf("[PortHandlerLinux::SetCustomBaudrate] TIOCGSERIAL failed!\n");
218  return false;
219  }
220 
221  ss.flags = (ss.flags & ~ASYNC_SPD_MASK) | ASYNC_SPD_CUST;
222  ss.custom_divisor = (ss.baud_base + (speed / 2)) / speed;
223  int closest_speed = ss.baud_base / ss.custom_divisor;
224 
225  if(closest_speed < speed * 98 / 100 || closest_speed > speed * 102 / 100)
226  {
227  printf("[PortHandlerLinux::SetCustomBaudrate] Cannot set speed to %d, closest is %d \n", speed, closest_speed);
228  return false;
229  }
230 
231  if(ioctl(socket_fd_, TIOCSSERIAL, &ss) < 0)
232  {
233  printf("[PortHandlerLinux::SetCustomBaudrate] TIOCSSERIAL failed!\n");
234  return false;
235  }
236 
237  tx_time_per_byte = (1000.0 / (double)speed) * 10.0;
238  return true;
239 }
240 
241 int PortHandlerLinux::getCFlagBaud(int baudrate)
242 {
243  switch(baudrate)
244  {
245  case 9600:
246  return B9600;
247  case 19200:
248  return B19200;
249  case 38400:
250  return B38400;
251  case 57600:
252  return B57600;
253  case 115200:
254  return B115200;
255  case 230400:
256  return B230400;
257  case 460800:
258  return B460800;
259  case 500000:
260  return B500000;
261  case 576000:
262  return B576000;
263  case 921600:
264  return B921600;
265  case 1000000:
266  return B1000000;
267  case 1152000:
268  return B1152000;
269  case 1500000:
270  return B1500000;
271  case 2000000:
272  return B2000000;
273  case 2500000:
274  return B2500000;
275  case 3000000:
276  return B3000000;
277  case 3500000:
278  return B3500000;
279  case 4000000:
280  return B4000000;
281  default:
282  return -1;
283  }
284 }
285 
286 #endif
void clearPort()
The function that clears the port @description The function clears the port.
char * getPortName()
The function that returns port name set into the port handler @description The function returns curre...
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler @description The function sets baudrate into th...
bool isPacketTimeout()
The function that checks whether packet timeout is occurred @description The function checks whether ...
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout @description The function set...
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer @description The fun...
void setPortName(const char *port_name)
The function that sets port name into the port handler @description The function sets port name into ...
int getBaudRate()
The function that returns current baudrate set into the port handler @description The function return...
void closePort()
The function that closes the port @description The function closes the port.
int readPort(uint8_t *packet, int length)
The function that reads bytes from the port buffer @description The function gets bytes from the port...
PortHandlerLinux(const char *port_name)
The function that initializes instance of PortHandler and gets port_name @description The function in...
int writePort(uint8_t *packet, int length)
The function that writes bytes on the port buffer @description The function writes bytes on the port ...