net_serial.cpp
Go to the documentation of this file.
00001 /*
00002  *  RPLIDAR SDK
00003  *
00004  *  Copyright (c) 2009 - 2014 RoboPeak Team
00005  *  http://www.robopeak.com
00006  *  Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
00007  *  http://www.slamtec.com
00008  *
00009  */
00010 /*
00011  * Redistribution and use in source and binary forms, with or without
00012  * modification, are permitted provided that the following conditions are met:
00013  *
00014  * 1. Redistributions of source code must retain the above copyright notice,
00015  *    this list of conditions and the following disclaimer.
00016  *
00017  * 2. Redistributions in binary form must reproduce the above copyright notice,
00018  *    this list of conditions and the following disclaimer in the documentation
00019  *    and/or other materials provided with the distribution.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
00023  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
00024  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00025  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
00026  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
00027  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
00028  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
00029  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
00030  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
00031  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00032  *
00033  */
00034 
00035 #include "arch/linux/arch_linux.h"
00036 #include "arch/linux/net_serial.h"
00037 #include <termios.h>
00038 #include <sys/select.h>
00039 
00040 namespace rp{ namespace arch{ namespace net{
00041 
00042 raw_serial::raw_serial()
00043     : rp::hal::serial_rxtx()
00044     , _baudrate(0)
00045     , _flags(0)
00046     , serial_fd(-1)
00047 {
00048     _init();
00049 }
00050 
00051 raw_serial::~raw_serial()
00052 {
00053     close();
00054 
00055 }
00056 
00057 bool raw_serial::open()
00058 {
00059     return open(_portName, _baudrate, _flags);
00060 }
00061 
00062 bool raw_serial::bind(const char * portname, uint32_t baudrate, uint32_t flags)
00063 {   
00064     strncpy(_portName, portname, sizeof(_portName));
00065     _baudrate = baudrate;
00066     _flags    = flags;
00067     return true;
00068 }
00069 
00070 bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
00071 {
00072     if (isOpened()) close();
00073     
00074     serial_fd = ::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
00075 
00076     if (serial_fd == -1) return false;
00077 
00078     struct termios options, oldopt;
00079     tcgetattr(serial_fd, &oldopt);
00080     bzero(&options,sizeof(struct termios));
00081 
00082     _u32 termbaud = getTermBaudBitmap(baudrate);
00083 
00084     if (termbaud == (_u32)-1) {
00085         close();
00086         return false;
00087     }
00088     cfsetispeed(&options, termbaud);
00089     cfsetospeed(&options, termbaud);
00090     
00091     // enable rx and tx
00092     options.c_cflag |= (CLOCAL | CREAD);
00093 
00094 
00095     options.c_cflag &= ~PARENB; //no checkbit
00096     options.c_cflag &= ~CSTOPB; //1bit stop bit
00097 
00098     options.c_cflag &= ~CSIZE;
00099     options.c_cflag |= CS8; /* Select 8 data bits */
00100 
00101 #ifdef CNEW_RTSCTS
00102     options.c_cflag &= ~CNEW_RTSCTS; // no hw flow control
00103 #endif
00104 
00105     options.c_iflag &= ~(IXON | IXOFF | IXANY); // no sw flow control
00106 
00107     // raw input mode   
00108     options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
00109     // raw output mode   
00110     options.c_oflag &= ~OPOST;
00111     
00112     tcflush(serial_fd,TCIFLUSH); 
00113 
00114     if (fcntl(serial_fd, F_SETFL, FNDELAY))
00115     {
00116         close();
00117         return false;
00118     }
00119     if (tcsetattr(serial_fd, TCSANOW, &options))
00120     {
00121         close();
00122         return false;
00123     }
00124 
00125     _is_serial_opened = true;
00126 
00127     //Clear the DTR bit to let the motor spin
00128     clearDTR();
00129     
00130     return true;
00131 }
00132 
00133 void raw_serial::close()
00134 {
00135     if (serial_fd != -1)
00136         ::close(serial_fd);
00137     serial_fd = -1;
00138     
00139     _is_serial_opened = false;
00140 }
00141 
00142 int raw_serial::senddata(const unsigned char * data, size_t size)
00143 {
00144 // FIXME: non-block io should be used
00145     if (!isOpened()) return 0;
00146 
00147     if (data == NULL || size ==0) return 0;
00148     
00149     size_t tx_len = 0;
00150     required_tx_cnt = 0;
00151     do {
00152         int ans = ::write(serial_fd, data + tx_len, size-tx_len);
00153         
00154         if (ans == -1) return tx_len;
00155         
00156         tx_len += ans;
00157         required_tx_cnt = tx_len;
00158     }while (tx_len<size);
00159     
00160     
00161     return tx_len;
00162 }
00163 
00164 
00165 int raw_serial::recvdata(unsigned char * data, size_t size)
00166 {
00167     if (!isOpened()) return 0;
00168     
00169     int ans = ::read(serial_fd, data, size);
00170     
00171     if (ans == -1) ans=0;
00172     required_rx_cnt = ans;
00173     return ans;
00174 }
00175 
00176 
00177 void raw_serial::flush( _u32 flags)
00178 {
00179     tcflush(serial_fd,TCIFLUSH); 
00180 }
00181 
00182 int raw_serial::waitforsent(_u32 timeout, size_t * returned_size)
00183 {
00184     if (returned_size) *returned_size = required_tx_cnt;
00185     return 0;
00186 }
00187 
00188 int raw_serial::waitforrecv(_u32 timeout, size_t * returned_size)
00189 {
00190     if (!isOpened() ) return -1;
00191    
00192     if (returned_size) *returned_size = required_rx_cnt;
00193     return 0;
00194 }
00195 
00196 int raw_serial::waitfordata(size_t data_count, _u32 timeout, size_t * returned_size)
00197 {
00198     size_t length = 0;
00199     if (returned_size==NULL) returned_size=(size_t *)&length;
00200     *returned_size = 0;
00201 
00202     int max_fd;
00203     fd_set input_set;
00204     struct timeval timeout_val;
00205 
00206     /* Initialize the input set */
00207     FD_ZERO(&input_set);
00208     FD_SET(serial_fd, &input_set);
00209     max_fd = serial_fd + 1;
00210 
00211     /* Initialize the timeout structure */
00212     timeout_val.tv_sec = timeout / 1000;
00213     timeout_val.tv_usec = (timeout % 1000) * 1000;
00214 
00215     if ( isOpened() )
00216     {
00217         if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00218         if (*returned_size >= data_count)
00219         {
00220             return 0;
00221         }
00222     }
00223 
00224     while ( isOpened() )
00225     {
00226         /* Do the select */
00227         int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
00228 
00229         if (n < 0)
00230         {
00231             // select error
00232             return ANS_DEV_ERR;
00233         }
00234         else if (n == 0)
00235         {
00236             // time out
00237             return ANS_TIMEOUT;
00238         }
00239         else
00240         {
00241             // data avaliable
00242             assert (FD_ISSET(serial_fd, &input_set));
00243 
00244 
00245             if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00246             if (*returned_size >= data_count)
00247             {
00248                 return 0;
00249             }
00250             else 
00251             {
00252                 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
00253                 int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
00254                 if (remain_timeout > expect_remain_time)
00255                     usleep(expect_remain_time);
00256             }
00257         }
00258         
00259     }
00260 
00261     return ANS_DEV_ERR;
00262 }
00263 
00264 size_t raw_serial::rxqueue_count()
00265 {
00266     if  ( !isOpened() ) return 0;
00267     size_t remaining;
00268     
00269     if (::ioctl(serial_fd, FIONREAD, &remaining) == -1) return 0;
00270     return remaining;
00271 }
00272 
00273 void raw_serial::setDTR()
00274 {
00275     if ( !isOpened() ) return;
00276 
00277     uint32_t dtr_bit = TIOCM_DTR;
00278     ioctl(serial_fd, TIOCMBIS, &dtr_bit);
00279 }
00280 
00281 void raw_serial::clearDTR()
00282 {
00283     if ( !isOpened() ) return;
00284 
00285     uint32_t dtr_bit = TIOCM_DTR;
00286     ioctl(serial_fd, TIOCMBIC, &dtr_bit);
00287 }
00288 
00289 void raw_serial::_init()
00290 {
00291     serial_fd = 0;  
00292     _portName[0] = 0;
00293     required_tx_cnt = required_rx_cnt = 0;
00294 }
00295 
00296 
00297 
00298 _u32 raw_serial::getTermBaudBitmap(_u32 baud)
00299 {
00300 #define BAUD_CONV( _baud_) case _baud_:  return B##_baud_ 
00301 switch (baud) {
00302         BAUD_CONV(1200);
00303         BAUD_CONV(1800);
00304         BAUD_CONV(2400);
00305         BAUD_CONV(4800);
00306         BAUD_CONV(9600);
00307         BAUD_CONV(19200);
00308         BAUD_CONV(38400);
00309         BAUD_CONV(57600);
00310         BAUD_CONV(115200);
00311         BAUD_CONV(230400);
00312         BAUD_CONV(460800);
00313         BAUD_CONV(500000);
00314         BAUD_CONV(576000);
00315         BAUD_CONV(921600);
00316         BAUD_CONV(1000000);
00317         BAUD_CONV(1152000);
00318         BAUD_CONV(1500000);
00319         BAUD_CONV(2000000);
00320         BAUD_CONV(2500000);
00321         BAUD_CONV(3000000);
00322         BAUD_CONV(3500000);
00323         BAUD_CONV(4000000);
00324     }
00325     return -1;
00326 }
00327 
00328 }}} //end rp::arch::net
00329 
00330 //begin rp::hal
00331 namespace rp{ namespace hal{
00332 
00333 serial_rxtx * serial_rxtx::CreateRxTx()
00334 {
00335     return new rp::arch::net::raw_serial();
00336 }
00337 
00338 void serial_rxtx::ReleaseRxTx(serial_rxtx *rxtx)
00339 {
00340     delete rxtx;
00341 }
00342 
00343 }} //end rp::hal


rplidar_ros
Author(s):
autogenerated on Fri Dec 16 2016 03:59:16