CerealPort.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita on 01/10/2010
00036 *********************************************************************/
00037 #include <stdio.h>
00038 #include <string.h>
00039 #include <errno.h>
00040 #include <termios.h>
00041 #include <math.h>
00042 #include <poll.h>
00043 #include <signal.h>
00044 #include <fcntl.h>
00045 #include <iostream>
00046 #include <fstream>
00047 #include <stdexcept>
00048 
00049 #include "cereal_port/CerealPort.h"
00050 
00052 #define CEREAL_EXCEPT(except, msg, ...) \
00053 { \
00054     char buf[1000]; \
00055     snprintf(buf, 1000, msg " (in cereal::CerealPort::%s)" , ##__VA_ARGS__, __FUNCTION__); \
00056     throw except(buf); \
00057 }
00058 
00059 cereal::CerealPort::CerealPort() : fd_(-1)
00060 {
00061         stream_thread_ = NULL;
00062 }
00063 
00064 cereal::CerealPort::~CerealPort()
00065 {
00066         if(portOpen()) close();
00067 }
00068 
00069 void cereal::CerealPort::open(const char * port_name, int baud_rate)
00070 {
00071         if(portOpen()) close();
00072   
00073         // Make IO non blocking. This way there are no race conditions that
00074         // cause blocking when a badly behaving process does a read at the same
00075         // time as us. Will need to switch to blocking for writes or errors
00076         // occur just after a replug event.
00077         fd_ = ::open(port_name, O_RDWR | O_NONBLOCK | O_NOCTTY);
00078 
00079         if(fd_ == -1)
00080         {
00081                 const char *extra_msg = "";
00082                 switch(errno)
00083                 {
00084                         case EACCES:
00085                         extra_msg = "You probably don't have premission to open the port for reading and writing.";
00086                         break;
00087 
00088                         case ENOENT:
00089                         extra_msg = "The requested port does not exist. Is the hokuyo connected? Was the port name misspelled?";
00090                         break;
00091                 }
00092                 CEREAL_EXCEPT(cereal::Exception, "Failed to open port: %s. %s (errno = %d). %s", port_name, strerror(errno), errno, extra_msg);
00093         }
00094         
00095         try
00096         {       
00097                 struct flock fl;
00098                 fl.l_type = F_WRLCK;
00099                 fl.l_whence = SEEK_SET;
00100                 fl.l_start = 0;
00101                 fl.l_len = 0;
00102                 fl.l_pid = getpid();
00103 
00104                 if(fcntl(fd_, F_SETLK, &fl) != 0)
00105                         CEREAL_EXCEPT(cereal::Exception, "Device %s is already locked. Try 'lsof | grep %s' to find other processes that currently have the port open.", port_name, port_name);
00106 
00107                 // Settings for USB?
00108                 struct termios newtio;
00109                 tcgetattr(fd_, &newtio);
00110                 memset (&newtio.c_cc, 0, sizeof (newtio.c_cc));
00111                 newtio.c_cflag = CS8 | CLOCAL | CREAD;
00112                 newtio.c_iflag = IGNPAR;
00113                 newtio.c_oflag = 0;
00114                 newtio.c_lflag = 0;
00115                 cfsetspeed(&newtio, baud_rate);
00116                 baud_ = baud_rate;
00117 
00118                 // Activate new settings
00119                 tcflush(fd_, TCIFLUSH);
00120                 if(tcsetattr(fd_, TCSANOW, &newtio) < 0)
00121                         CEREAL_EXCEPT(cereal::Exception, "Unable to set serial port attributes. The port you specified (%s) may not be a serial port.", port_name); 
00122                 usleep (200000);
00123         }
00124         catch(cereal::Exception& e)
00125         {
00126                 // These exceptions mean something failed on open and we should close
00127                 if(fd_ != -1) ::close(fd_);
00128                 fd_ = -1;
00129                 throw e;
00130         }
00131 }
00132 
00133 void cereal::CerealPort::close()
00134 {
00135         int retval = 0;
00136         
00137         retval = ::close(fd_);
00138 
00139         fd_ = -1;
00140 
00141         if(retval != 0)
00142                 CEREAL_EXCEPT(cereal::Exception, "Failed to close port properly -- error = %d: %s\n", errno, strerror(errno));
00143 }
00144 
00145 int cereal::CerealPort::write(const char * data, int length)
00146 {
00147         int len = length==-1 ? strlen(data) : length;
00148 
00149         // IO is currently non-blocking. This is what we want for the more cerealon read case.
00150         int origflags = fcntl(fd_, F_GETFL, 0);
00151         fcntl(fd_, F_SETFL, origflags & ~O_NONBLOCK); // TODO: @todo can we make this all work in non-blocking?
00152         int retval = ::write(fd_, data, len);
00153         fcntl(fd_, F_SETFL, origflags | O_NONBLOCK);
00154 
00155         if(retval == len) return retval;
00156         else CEREAL_EXCEPT(cereal::Exception, "write failed");
00157 }
00158 
00159 int cereal::CerealPort::read(char * buffer, int max_length, int timeout)
00160 {
00161         int ret;
00162 
00163         struct pollfd ufd[1];
00164         int retval;
00165         ufd[0].fd = fd_;
00166         ufd[0].events = POLLIN;
00167 
00168         if(timeout == 0) timeout = -1; // For compatibility with former behavior, 0 means no timeout. For poll, negative means no timeout.
00169 
00170         if((retval = poll(ufd, 1, timeout)) < 0) CEREAL_EXCEPT(cereal::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00171 
00172         if(retval == 0) CEREAL_EXCEPT(cereal::TimeoutException, "timeout reached");
00173                 
00174         if(ufd[0].revents & POLLERR) CEREAL_EXCEPT(cereal::Exception, "error on socket, possibly unplugged");
00175                 
00176     ret = ::read(fd_, buffer, max_length);
00177                 
00178         if(ret == -1 && errno != EAGAIN && errno != EWOULDBLOCK) CEREAL_EXCEPT(cereal::Exception, "read failed");
00179         
00180         return ret;
00181 }
00182 
00183 int cereal::CerealPort::readBytes(char * buffer, int length, int timeout)
00184 {
00185         int ret;
00186         int current = 0;
00187 
00188         struct pollfd ufd[1];
00189         int retval;
00190         ufd[0].fd = fd_;
00191         ufd[0].events = POLLIN;
00192 
00193         if(timeout == 0) timeout = -1; // For compatibility with former behavior, 0 means no timeout. For poll, negative means no timeout.
00194 
00195         while(current < length)
00196         {
00197                 if((retval = poll(ufd, 1, timeout)) < 0) CEREAL_EXCEPT(cereal::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00198 
00199                 if(retval == 0) CEREAL_EXCEPT(cereal::TimeoutException, "timeout reached");
00200                 
00201                 if(ufd[0].revents & POLLERR) CEREAL_EXCEPT(cereal::Exception, "error on socket, possibly unplugged");
00202                 
00203         ret = ::read(fd_, &buffer[current], length-current);
00204                 
00205                 if(ret == -1 && errno != EAGAIN && errno != EWOULDBLOCK) CEREAL_EXCEPT(cereal::Exception, "read failed");
00206 
00207                 current += ret;
00208         }
00209         return current;
00210 }
00211 
00212 int cereal::CerealPort::readLine(char * buffer, int length, int timeout)
00213 {
00214         int ret;
00215         int current = 0;
00216 
00217         struct pollfd ufd[1];
00218         int retval;
00219         ufd[0].fd = fd_;
00220         ufd[0].events = POLLIN;
00221 
00222         if(timeout == 0) timeout = -1; // For compatibility with former behavior, 0 means no timeout. For poll, negative means no timeout.
00223 
00224         while(current < length-1)
00225         {
00226                 if(current > 0)
00227                         if(buffer[current-1] == '\n')
00228                                 return current;
00229 
00230                 if((retval = poll(ufd, 1, timeout)) < 0) CEREAL_EXCEPT(cereal::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00231 
00232                 if(retval == 0) CEREAL_EXCEPT(cereal::TimeoutException, "timeout reached");
00233                 
00234                 if(ufd[0].revents & POLLERR) CEREAL_EXCEPT(cereal::Exception, "error on socket, possibly unplugged");
00235                 
00236         ret = ::read(fd_, &buffer[current], length-current);
00237                 
00238                 if(ret == -1 && errno != EAGAIN && errno != EWOULDBLOCK) CEREAL_EXCEPT(cereal::Exception, "read failed");
00239 
00240                 current += ret;
00241         }
00242         CEREAL_EXCEPT(cereal::Exception, "buffer filled without end of line being found");
00243 }
00244 
00245 bool cereal::CerealPort::readLine(std::string * buffer, int timeout)
00246 {
00247         int ret;
00248 
00249         struct pollfd ufd[1];
00250         int retval;
00251         ufd[0].fd = fd_;
00252         ufd[0].events = POLLIN;
00253 
00254         if(timeout == 0) timeout = -1; // For compatibility with former behavior, 0 means no timeout. For poll, negative means no timeout.
00255 
00256         buffer->clear();
00257         while(buffer->size() < buffer->max_size()/2)
00258         {
00259                 // Look for the end char
00260                 ret = buffer->find_first_of('\n');
00261                 if(ret > 0)
00262                 {
00263                         // If it is there clear everything after it and return
00264                         buffer->erase(ret+1, buffer->size()-ret-1);
00265                         return true;
00266                 }
00267 
00268                 if((retval = poll(ufd, 1, timeout)) < 0) CEREAL_EXCEPT(cereal::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00269 
00270                 if(retval == 0) CEREAL_EXCEPT(cereal::TimeoutException, "timeout reached");
00271                 
00272                 if(ufd[0].revents & POLLERR) CEREAL_EXCEPT(cereal::Exception, "error on socket, possibly unplugged");
00273                 
00274         char temp_buffer[128];
00275         ret = ::read(fd_, temp_buffer, 128);
00276                 
00277                 if(ret == -1 && errno != EAGAIN && errno != EWOULDBLOCK) CEREAL_EXCEPT(cereal::Exception, "read failed");
00278 
00279                 // Append the new data to the buffer
00280         try{ buffer->append(temp_buffer, ret); }
00281         catch(std::length_error& le)
00282         {
00283             CEREAL_EXCEPT(cereal::Exception, "buffer filled without reaching end of data stream");
00284         }
00285         }
00286         CEREAL_EXCEPT(cereal::Exception, "buffer filled without end of line being found");
00287 }
00288 
00289 bool cereal::CerealPort::readBetween(std::string * buffer, char start, char end, int timeout)
00290 {
00291         int ret;
00292 
00293         struct pollfd ufd[1];
00294         static std::string erased;
00295         int retval;
00296         ufd[0].fd = fd_;
00297         ufd[0].events = POLLIN;
00298 
00299         if(timeout == 0) timeout = -1; // For compatibility with former behavior, 0 means no timeout. For poll, negative means no timeout.
00300 
00301         // Clear the buffer before we start
00302         buffer->clear();
00303         while(buffer->size() < buffer->max_size()/2)
00304         {
00305                 if((retval = poll(ufd, 1, timeout)) < 0) CEREAL_EXCEPT(cereal::Exception, "poll failed -- error = %d: %s", errno, strerror(errno));
00306                 
00307                 if(retval == 0) CEREAL_EXCEPT(cereal::TimeoutException, "timeout reached");
00308                 
00309                 if(ufd[0].revents & POLLERR) CEREAL_EXCEPT(cereal::Exception, "error on socket, possibly unplugged");
00310 
00311                 // Append erased characters in last iteration
00312                 if(!erased.empty())
00313                 {
00314                         try
00315                         { 
00316                                 buffer->append(erased);
00317                                 erased.clear();
00318                         }
00319                 catch(std::length_error& le)
00320                 {
00321                     CEREAL_EXCEPT(cereal::Exception, "failed to append erased to buffer");
00322                 }
00323             }
00324                 
00325                 char temp_buffer[3];
00326                 ret = ::read(fd_, temp_buffer, 3);
00327         
00328                 if(ret == -1 && errno != EAGAIN && errno != EWOULDBLOCK) CEREAL_EXCEPT(cereal::Exception, "read failed");
00329         
00330                 // Append the new data to the buffer
00331                 try{ buffer->append(temp_buffer, ret); }
00332         catch(std::length_error& le)
00333         {
00334             CEREAL_EXCEPT(cereal::Exception, "buffer filled without reaching end of data stream");
00335         }
00336         
00337         // Look for the start char
00338         ret = buffer->find_first_of(start);
00339         // If it is not on the buffer, clear it
00340         if(ret == -1) buffer->clear();
00341         // If it is there, but not on the first position clear everything behind it
00342         else if(ret > 0) buffer->erase(0, ret);
00343                 
00344                 // Look for the end char
00345                 ret = buffer->find_first_of(end);
00346                 if(ret > 0)
00347                 {
00348                         // If it is there clear everything after it and return
00349                         erased = buffer->substr(ret+1, buffer->size()-ret-1);
00350                         //std::cout << "sobra |" << erased << "|\n";
00351                         buffer->erase(ret+1, buffer->size()-ret-1);
00352                         return true;
00353                 }
00354         }
00355         CEREAL_EXCEPT(cereal::Exception, "buffer filled without reaching end of data stream");
00356 }
00357 
00358 int cereal::CerealPort::flush()
00359 {
00360           int retval = tcflush(fd_, TCIOFLUSH);
00361           if(retval != 0) CEREAL_EXCEPT(cereal::Exception, "tcflush failed");
00362           
00363           return retval;
00364 }
00365 
00366 bool cereal::CerealPort::startReadStream(boost::function<void(char*, int)> f)
00367 {
00368         if(stream_thread_ != NULL) return false;
00369 
00370         stream_stopped_ = false;
00371         stream_paused_ = false;
00372         
00373         readCallback = f;
00374         
00375         stream_thread_ = new boost::thread(boost::bind(&cereal::CerealPort::readThread, this));
00376         return true;
00377 }
00378 
00379 void cereal::CerealPort::readThread()
00380 {
00381         char data[MAX_LENGTH];
00382         int ret;
00383 
00384         struct pollfd ufd[1];
00385         ufd[0].fd = fd_;
00386         ufd[0].events = POLLIN;
00387         
00388         while(!stream_stopped_)
00389         {
00390                 if(!stream_paused_)
00391                 {
00392                         if(poll(ufd, 1, 10) > 0)
00393                         {
00394                                 if(!(ufd[0].revents & POLLERR))
00395                                 {
00396                                         ret = ::read(fd_, data, MAX_LENGTH);
00397                                         if(ret>0)
00398                                         {
00399                                                 readCallback(data, ret);
00400                                         }
00401                                 }
00402                         }
00403                 }
00404         }
00405 }
00406 
00407 bool cereal::CerealPort::startReadLineStream(boost::function<void(std::string*)> f)
00408 {
00409         if(stream_thread_ != NULL) return false;
00410 
00411         stream_stopped_ = false;
00412         stream_paused_ = false;
00413         
00414         readLineCallback = f;
00415         
00416         stream_thread_ = new boost::thread(boost::bind(&cereal::CerealPort::readLineThread, this));
00417         return true;
00418 }
00419 
00420 void cereal::CerealPort::readLineThread()
00421 {
00422         std::string data;
00423         bool error = false;
00424 
00425         while(!stream_stopped_)
00426         {
00427                 if(!stream_paused_)
00428                 {
00429                         error = false;
00430                         try{ readLine(&data, 100); }
00431                         catch(cereal::Exception& e)
00432                         { 
00433                                 error = true;
00434                         }
00435                         
00436                         if(!error && data.size()>0) readLineCallback(&data);
00437                 }
00438         }
00439 }
00440 
00441 bool cereal::CerealPort::startReadBetweenStream(boost::function<void(std::string*)> f, char start, char end)
00442 {
00443         if(stream_thread_ != NULL) return false;
00444 
00445         stream_stopped_ = false;
00446         stream_paused_ = false;
00447         
00448         readBetweenCallback = f;
00449         
00450         stream_thread_ = new boost::thread(boost::bind(&cereal::CerealPort::readBetweenThread, this, start, end));
00451         return true;
00452 }
00453 
00454 void cereal::CerealPort::readBetweenThread(char start, char end)
00455 {
00456         std::string data;
00457         bool error = false;
00458 
00459         while(!stream_stopped_)
00460         {
00461                 if(!stream_paused_)
00462                 {
00463                         error = false;
00464                         try{ readBetween(&data, start, end, 100); }
00465                         catch(cereal::Exception& e)
00466                         { 
00467                                 error = true;
00468                         }
00469                         
00470                         if(!error && data.size()>0) readBetweenCallback(&data);
00471                 }
00472         }
00473 }
00474 
00475 void cereal::CerealPort::stopStream()
00476 {
00477         stream_stopped_ = true;
00478         stream_thread_->join();
00479         
00480         delete stream_thread_;
00481         stream_thread_ = NULL;
00482 }
00483 
00484 void cereal::CerealPort::pauseStream()
00485 {
00486         stream_paused_ = true;
00487 }
00488 
00489 void cereal::CerealPort::resumeStream()
00490 {
00491         stream_paused_ = false;
00492 }
00493 
00494 // EOF


cereal_port
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:25:14