serialcomm_s300.cpp
Go to the documentation of this file.
00001 /*
00002  *
00003  * serialcomm_s300.cpp
00004  *
00005  *
00006  * Copyright (C) 2010
00007  * Autonomous Intelligent Systems Group
00008  * University of Bonn, Germany
00009  *
00010  *
00011  * Authors: Andreas Hochrath, Torsten Fiolka
00012  *
00013  *
00014  * This program is free software; you can redistribute it and/or modify
00015  * it under the terms of the GNU General Public License as published by
00016  * the Free Software Foundation; either version 3 of the License, or
00017  * (at your option) any later version.
00018  *
00019  * This program is distributed in the hope that it will be useful,
00020  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00021  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00022  * GNU General Public License for more details.
00023  *
00024  * You should have received a copy of the GNU General Public License
00025  * along with this program; if not, write to the Free Software
00026  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
00027  *
00028  *
00029  * Origin:
00030  *  Player - One Hell of a Robot Server
00031  *  serialstream.cc & sicks3000.cc
00032  *  Copyright (C) 2003
00033  *     Brian Gerkey
00034  *  Copyright (C) 2000
00035  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00036  *
00037  */
00038 
00039 #include "serialcomm_s300.h"
00040 
00041 #include <assert.h>
00042 #include <math.h>
00043 #include <errno.h>
00044 #include <fcntl.h>
00045 #include <stdio.h>
00046 #include <stdlib.h>
00047 #include <string.h>
00048 #include <netinet/in.h>
00049 #include <sys/types.h>
00050 #include <sys/stat.h>
00051 
00052 #include <termios.h>
00053 #include <unistd.h>
00054 #include <sys/ioctl.h>
00055 
00056 #include <iostream>
00057 
00058 SerialCommS300::SerialCommS300()
00059 {
00060   m_rxCount = 0;
00061   m_ranges = NULL;
00062 }
00063 
00064 SerialCommS300::~SerialCommS300()
00065 {
00066   disconnect();
00067 }
00068 
00069 int SerialCommS300::connect(const std::string& deviceName, unsigned int baudRate)
00070 {
00071 
00072   m_fd = ::open(deviceName.c_str(), O_RDWR | O_NOCTTY | O_NDELAY | O_NONBLOCK);
00073   if (m_fd < 0)
00074   {
00075     std::cout << "SerialCommS300: unable to open serial port " << deviceName << "\n";
00076     return -1;
00077   }
00078 
00079   setFlags();
00080   if (setBaudRate(baudRateToBaudCode(baudRate)))
00081     return -1;
00082 
00083   tcflush(m_fd, TCIOFLUSH);
00084   usleep(1000);
00085   tcflush(m_fd, TCIFLUSH);
00086 
00087   return 0;
00088 
00089 }
00090 
00091 void SerialCommS300::setFlags()
00092 {
00093 
00094   // set up new settings
00095   struct termios term;
00096   memset(&term, 0, sizeof(term));
00097 
00098   tcgetattr(m_fd, &term);
00099 
00100   term.c_cc[VMIN] = 0;
00101   term.c_cc[VTIME] = 0;
00102   term.c_cflag = CS8 | CREAD;
00103   term.c_iflag = INPCK;
00104   term.c_oflag = 0;
00105   term.c_lflag = 0;
00106 
00107   if (tcsetattr(m_fd, TCSANOW, &term) < 0)
00108     std::cout << "SerialCommS300: failed to set tty device attributes";
00109   tcflush(m_fd, TCIOFLUSH);
00110 
00111 }
00112 
00113 int SerialCommS300::setBaudRate(int baudRate)
00114 {
00115 
00116   struct termios term;
00117 
00118   if (tcgetattr(m_fd, &term) < 0)
00119   {
00120     std::cout << "SerialCommS300: unable to get device attributes\n";
00121     return 1;
00122   }
00123 
00124   if (cfsetispeed(&term, baudRate) < 0 || cfsetospeed(&term, baudRate) < 0)
00125   {
00126     std::cout << "SerialCommS300: failed to set serial baud rate " << baudRate << "\n";
00127     return 1;
00128   }
00129 
00130   if (tcsetattr(m_fd, TCSAFLUSH, &term) < 0)
00131   {
00132     std::cout << "SerialCommS300: unable to set device attributes\n";
00133     return 1;
00134   }
00135 
00136   return 0;
00137 }
00138 
00139 int SerialCommS300::baudRateToBaudCode(int baudRate)
00140 {
00141   switch (baudRate)
00142   {
00143     case 38400:
00144       return B38400;
00145     case 115200:
00146       return B115200;
00147     case 500000:
00148       return B500000;
00149     default:
00150       return B500000;
00151   };
00152 }
00153 
00154 int SerialCommS300::disconnect()
00155 {
00156   ::close(m_fd);
00157   return 0;
00158 }
00159 
00160 static const unsigned short crc_table[256] = {0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, 0x8108,
00161                                               0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, 0x1231, 0x0210,
00162                                               0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, 0x9339, 0x8318, 0xb37b,
00163                                               0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de, 0x2462, 0x3443, 0x0420, 0x1401,
00164                                               0x64e6, 0x74c7, 0x44a4, 0x5485, 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee,
00165                                               0xf5cf, 0xc5ac, 0xd58d, 0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6,
00166                                               0x5695, 0x46b4, 0xb75b, 0xa77a, 0x9719, 0x8738, 0xf7df, 0xe7fe, 0xd79d,
00167                                               0xc7bc, 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823,
00168                                               0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, 0x5af5,
00169                                               0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, 0xdbfd, 0xcbdc,
00170                                               0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, 0x6ca6, 0x7c87, 0x4ce4,
00171                                               0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41, 0xedae, 0xfd8f, 0xcdec, 0xddcd,
00172                                               0xad2a, 0xbd0b, 0x8d68, 0x9d49, 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13,
00173                                               0x2e32, 0x1e51, 0x0e70, 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a,
00174                                               0x9f59, 0x8f78, 0x9188, 0x81a9, 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e,
00175                                               0xe16f, 0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067,
00176                                               0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e, 0x02b1,
00177                                               0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, 0xb5ea, 0xa5cb,
00178                                               0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, 0x34e2, 0x24c3, 0x14a0,
00179                                               0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 0xa7db, 0xb7fa, 0x8799, 0x97b8,
00180                                               0xe75f, 0xf77e, 0xc71d, 0xd73c, 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657,
00181                                               0x7676, 0x4615, 0x5634, 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9,
00182                                               0xb98a, 0xa9ab, 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882,
00183                                               0x28a3, 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a,
00184                                               0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, 0xfd2e,
00185                                               0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, 0x9de8, 0x8dc9, 0x7c26, 0x6c07,
00186                                               0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, 0xef1f, 0xff3e, 0xcf5d,
00187                                               0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, 0x6e17, 0x7e36, 0x4e55, 0x5e74,
00188                                               0x2e93, 0x3eb2, 0x0ed1, 0x1ef0};
00189 
00190 unsigned short SerialCommS300::createCRC(unsigned char* data, ssize_t length)
00191 {
00192 
00193   unsigned short CRC_16 = 0xFFFF;
00194   unsigned short i;
00195 
00196   for (i = 0; i < length; i++)
00197   {
00198     CRC_16 = (CRC_16 << 8) ^ (crc_table[(CRC_16 >> 8) ^ (data[i])]);
00199   }
00200 
00201   return CRC_16;
00202 
00203 }
00204 
00205 int SerialCommS300::readData()
00206 {
00207 
00208   if (RX_BUFFER_SIZE - m_rxCount > 0)
00209   {
00210 
00211     // Read a packet from the laser
00212     int len = read(m_fd, &m_rxBuffer[m_rxCount], RX_BUFFER_SIZE - m_rxCount);
00213     if (len == 0)
00214     {
00215       return -1;
00216     }
00217 
00218     if (len < 0)
00219     {
00220       std::cout << "SerialCommS300: error reading form serial port: " << strerror(errno) << "\n";
00221       return -1;
00222     }
00223 
00224     m_rxCount += len;
00225 
00226   }
00227 
00228   while (m_rxCount >= 22)
00229   {
00230 
00231     // find our continuous data header
00232     int ii;
00233     bool found = false;
00234     for (ii = 0; ii < m_rxCount - 22; ++ii)
00235     {
00236       if (memcmp(&m_rxBuffer[ii], "\0\0\0\0\0\0", 6) == 0)
00237       {
00238         memmove(m_rxBuffer, &m_rxBuffer[ii], m_rxCount - ii);
00239         m_rxCount -= ii;
00240         found = true;
00241         break;
00242       }
00243     }
00244 
00245     if (!found)
00246     {
00247       memmove(m_rxBuffer, &m_rxBuffer[ii], m_rxCount - ii);
00248       m_rxCount -= ii;
00249       return -1;
00250     }
00251 
00252     // get relevant bits of the header
00253     // size includes all data from the data block number
00254     // through to the end of the packet including the checksum
00255     unsigned short size = 2 * htons(*reinterpret_cast<unsigned short *> (&m_rxBuffer[6]));
00256     //printf("size %d", size);
00257     if (size > RX_BUFFER_SIZE - 26)
00258     {
00259       std::cout << "SerialCommS300: Requested Size of data is larger than the buffer size\n";
00260       memmove(m_rxBuffer, &m_rxBuffer[1], --m_rxCount);
00261       return -1;
00262     }
00263 
00264     // check if we have enough data yet
00265     if (size > m_rxCount - 4)
00266       return -1;
00267 
00268     unsigned short packet_checksum = *reinterpret_cast<unsigned short *> (&m_rxBuffer[size + 2]);
00269     unsigned short calc_checksum = createCRC(&m_rxBuffer[4], size - 2);
00270     if (packet_checksum != calc_checksum)
00271     {
00272       std::cout << "SerialCommS300: Checksum's dont match, thats bad (data packet size " << size << ")\n";
00273       memmove(m_rxBuffer, &m_rxBuffer[1], --m_rxCount);
00274       continue;
00275     }
00276     else
00277     {
00278       uint8_t* data = &m_rxBuffer[20];
00279       if (data[0] != data[1])
00280       {
00281         std::cout << "SerialCommS300: Bad type header bytes dont match\n";
00282       }
00283       else
00284       {
00285         if (data[0] == 0xAA)
00286         {
00287           std::cout << "SerialCommS300: We got a I/O data packet we dont know what to do with it\n";
00288         }
00289         else if (data[0] == 0xBB)
00290         {
00291 
00292           int data_count = (size - 22) / 2;
00293           if (data_count < 0)
00294           {
00295             std::cout << "SerialCommS300: bad data count (" << data_count << ")\n";
00296             memmove(m_rxBuffer, &m_rxBuffer[size + 4], m_rxCount - (size + 4));
00297             m_rxCount -= (size + 4);
00298             continue;
00299           }
00300 
00301           if (m_ranges)
00302             delete[] m_ranges;
00303 
00304           m_ranges = new float[data_count];
00305           m_rangesCount = data_count;
00306 
00307           for (int ii = 0; ii < data_count; ++ii)
00308           {
00309             unsigned short distance_cm = (*reinterpret_cast<unsigned short *> (&data[4 + 2 * ii]));
00310             distance_cm &= 0x1fff; // remove status bits
00311             m_ranges[ii] = static_cast<double> (distance_cm) / 100.0;
00312           }
00313 
00314           memmove(m_rxBuffer, &m_rxBuffer[size + 4], m_rxCount - (size + 4));
00315           m_rxCount -= (size + 4);
00316 
00317           return 0;
00318 
00319         }
00320         else if (data[0] == 0xCC)
00321         {
00322           std::cout << "SerialCommS300: We got a reflector data packet we dont know what to do with it\n";
00323         }
00324         else
00325         {
00326           std::cout << "SerialCommS300: We got an unknown packet\n";
00327         }
00328       }
00329     }
00330 
00331     memmove(m_rxBuffer, &m_rxBuffer[size + 4], m_rxCount - (size + 4));
00332     m_rxCount -= (size + 4);
00333     continue;
00334   }
00335 
00336   return -1;
00337 
00338 }
00339 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


sicks300
Author(s): Andreas Hochrath, Torsten Fiolka
autogenerated on Thu Apr 25 2013 17:26:53