port_handler_linux.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * Copyright 2017 ROBOTIS CO., LTD.
00003 *
00004 * Licensed under the Apache License, Version 2.0 (the "License");
00005 * you may not use this file except in compliance with the License.
00006 * You may obtain a copy of the License at
00007 *
00008 *     http://www.apache.org/licenses/LICENSE-2.0
00009 *
00010 * Unless required by applicable law or agreed to in writing, software
00011 * distributed under the License is distributed on an "AS IS" BASIS,
00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013 * See the License for the specific language governing permissions and
00014 * limitations under the License.
00015 *******************************************************************************/
00016 
00017 /* Author: zerom, Ryu Woon Jung (Leon) */
00018 
00019 #if defined(__linux__)
00020 
00021 #include <stdio.h>
00022 #include <fcntl.h>
00023 #include <string.h>
00024 #include <unistd.h>
00025 #include <termios.h>
00026 #include <time.h>
00027 #include <sys/time.h>
00028 #include <sys/ioctl.h>
00029 #include <linux/serial.h>
00030 
00031 #include "port_handler_linux.h"
00032 
00033 #define LATENCY_TIMER  16  // msec (USB latency timer)
00034                            // 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'.
00035                            // When you are going to use sync / bulk read, the latency timer should be loosen.
00036                            // the lower latency timer value, the faster communication speed.
00037 
00038                            // Note:
00039                            // You can check its value by:
00040                            // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
00041                            //
00042                            // If you think that the communication is too slow, type following after plugging the usb in to change the latency timer
00043                            //
00044                            // Method 1. Type following (you should do this everytime when the usb once was plugged out or the connection was dropped)
00045                            // $ echo 1 | sudo tee /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
00046                            // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
00047                            //
00048                            // 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,
00049                            // $ echo ACTION==\"add\", SUBSYSTEM==\"usb-serial\", DRIVER==\"ftdi_sio\", ATTR{latency_timer}=\"1\" > 99-dynamixelsdk-usb.rules
00050                            // $ sudo cp ./99-dynamixelsdk-usb.rules /etc/udev/rules.d/
00051                            // $ sudo udevadm control --reload-rules
00052                            // $ sudo udevadm trigger --action=add
00053                            // $ cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
00054                            //
00055                            // or if you have another good idea that can be an alternatives,
00056                            // please give us advice via github issue https://github.com/ROBOTIS-GIT/DynamixelSDK/issues
00057 
00058 using namespace dynamixel;
00059 
00060 PortHandlerLinux::PortHandlerLinux(const char *port_name)
00061   : socket_fd_(-1),
00062     baudrate_(DEFAULT_BAUDRATE_),
00063     packet_start_time_(0.0),
00064     packet_timeout_(0.0),
00065     tx_time_per_byte(0.0)
00066 {
00067   is_using_ = false;
00068   setPortName(port_name);
00069 }
00070 
00071 bool PortHandlerLinux::openPort()
00072 {
00073   return setBaudRate(baudrate_);
00074 }
00075 
00076 void PortHandlerLinux::closePort()
00077 {
00078   if(socket_fd_ != -1)
00079     close(socket_fd_);
00080   socket_fd_ = -1;
00081 }
00082 
00083 void PortHandlerLinux::clearPort()
00084 {
00085   tcflush(socket_fd_, TCIFLUSH);
00086 }
00087 
00088 void PortHandlerLinux::setPortName(const char *port_name)
00089 {
00090   strcpy(port_name_, port_name);
00091 }
00092 
00093 char *PortHandlerLinux::getPortName()
00094 {
00095   return port_name_;
00096 }
00097 
00098 // TODO: baud number ??
00099 bool PortHandlerLinux::setBaudRate(const int baudrate)
00100 {
00101   int baud = getCFlagBaud(baudrate);
00102 
00103   closePort();
00104 
00105   if(baud <= 0)   // custom baudrate
00106   {
00107     setupPort(B38400);
00108     baudrate_ = baudrate;
00109     return setCustomBaudrate(baudrate);
00110   }
00111   else
00112   {
00113     baudrate_ = baudrate;
00114     return setupPort(baud);
00115   }
00116 }
00117 
00118 int PortHandlerLinux::getBaudRate()
00119 {
00120   return baudrate_;
00121 }
00122 
00123 int PortHandlerLinux::getBytesAvailable()
00124 {
00125   int bytes_available;
00126   ioctl(socket_fd_, FIONREAD, &bytes_available);
00127   return bytes_available;
00128 }
00129 
00130 int PortHandlerLinux::readPort(uint8_t *packet, int length)
00131 {
00132   return read(socket_fd_, packet, length);
00133 }
00134 
00135 int PortHandlerLinux::writePort(uint8_t *packet, int length)
00136 {
00137   return write(socket_fd_, packet, length);
00138 }
00139 
00140 void PortHandlerLinux::setPacketTimeout(uint16_t packet_length)
00141 {
00142   packet_start_time_  = getCurrentTime();
00143   packet_timeout_     = (tx_time_per_byte * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
00144 }
00145 
00146 void PortHandlerLinux::setPacketTimeout(double msec)
00147 {
00148   packet_start_time_  = getCurrentTime();
00149   packet_timeout_     = msec;
00150 }
00151 
00152 bool PortHandlerLinux::isPacketTimeout()
00153 {
00154   if(getTimeSinceStart() > packet_timeout_)
00155   {
00156     packet_timeout_ = 0;
00157     return true;
00158   }
00159   return false;
00160 }
00161 
00162 double PortHandlerLinux::getCurrentTime()
00163 {
00164         struct timespec tv;
00165         clock_gettime(CLOCK_REALTIME, &tv);
00166         return ((double)tv.tv_sec * 1000.0 + (double)tv.tv_nsec * 0.001 * 0.001);
00167 }
00168 
00169 double PortHandlerLinux::getTimeSinceStart()
00170 {
00171   double time;
00172 
00173   time = getCurrentTime() - packet_start_time_;
00174   if(time < 0.0)
00175     packet_start_time_ = getCurrentTime();
00176 
00177   return time;
00178 }
00179 
00180 bool PortHandlerLinux::setupPort(int cflag_baud)
00181 {
00182   struct termios newtio;
00183 
00184   socket_fd_ = open(port_name_, O_RDWR|O_NOCTTY|O_NONBLOCK);
00185   if(socket_fd_ < 0)
00186   {
00187     printf("[PortHandlerLinux::SetupPort] Error opening serial port!\n");
00188     return false;
00189   }
00190 
00191   bzero(&newtio, sizeof(newtio)); // clear struct for new port settings
00192 
00193   newtio.c_cflag = cflag_baud | CS8 | CLOCAL | CREAD;
00194   newtio.c_iflag = IGNPAR;
00195   newtio.c_oflag      = 0;
00196   newtio.c_lflag      = 0;
00197   newtio.c_cc[VTIME]  = 0;
00198   newtio.c_cc[VMIN]   = 0;
00199 
00200   // clean the buffer and activate the settings for the port
00201   tcflush(socket_fd_, TCIFLUSH);
00202   tcsetattr(socket_fd_, TCSANOW, &newtio);
00203 
00204   tx_time_per_byte = (1000.0 / (double)baudrate_) * 10.0;
00205   return true;
00206 }
00207 
00208 bool PortHandlerLinux::setCustomBaudrate(int speed)
00209 {
00210   // try to set a custom divisor
00211   struct serial_struct ss;
00212   if(ioctl(socket_fd_, TIOCGSERIAL, &ss) != 0)
00213   {
00214     printf("[PortHandlerLinux::SetCustomBaudrate] TIOCGSERIAL failed!\n");
00215     return false;
00216   }
00217 
00218   ss.flags = (ss.flags & ~ASYNC_SPD_MASK) | ASYNC_SPD_CUST;
00219   ss.custom_divisor = (ss.baud_base + (speed / 2)) / speed;
00220   int closest_speed = ss.baud_base / ss.custom_divisor;
00221 
00222   if(closest_speed < speed * 98 / 100 || closest_speed > speed * 102 / 100)
00223   {
00224     printf("[PortHandlerLinux::SetCustomBaudrate] Cannot set speed to %d, closest is %d \n", speed, closest_speed);
00225     return false;
00226   }
00227 
00228   if(ioctl(socket_fd_, TIOCSSERIAL, &ss) < 0)
00229   {
00230     printf("[PortHandlerLinux::SetCustomBaudrate] TIOCSSERIAL failed!\n");
00231     return false;
00232   }
00233 
00234   tx_time_per_byte = (1000.0 / (double)speed) * 10.0;
00235   return true;
00236 }
00237 
00238 int PortHandlerLinux::getCFlagBaud(int baudrate)
00239 {
00240   switch(baudrate)
00241   {
00242     case 9600:
00243       return B9600;
00244     case 19200:
00245       return B19200;
00246     case 38400:
00247       return B38400;
00248     case 57600:
00249       return B57600;
00250     case 115200:
00251       return B115200;
00252     case 230400:
00253       return B230400;
00254     case 460800:
00255       return B460800;
00256     case 500000:
00257       return B500000;
00258     case 576000:
00259       return B576000;
00260     case 921600:
00261       return B921600;
00262     case 1000000:
00263       return B1000000;
00264     case 1152000:
00265       return B1152000;
00266     case 1500000:
00267       return B1500000;
00268     case 2000000:
00269       return B2000000;
00270     case 2500000:
00271       return B2500000;
00272     case 3000000:
00273       return B3000000;
00274     case 3500000:
00275       return B3500000;
00276     case 4000000:
00277       return B4000000;
00278     default:
00279       return -1;
00280   }
00281 }
00282 
00283 #endif


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11