Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
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
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
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
00099 bool PortHandlerLinux::setBaudRate(const int baudrate)
00100 {
00101 int baud = getCFlagBaud(baudrate);
00102
00103 closePort();
00104
00105 if(baud <= 0)
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));
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
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
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