uniserial.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Robert Bosch LLC.
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 Robert Bosch 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  *********************************************************************/
00036 
00037 //\Author Joshua Vasquez and Philip Roan, Robert Bosch LLC
00038 
00039 #include "uniserial/uniserial.hpp"
00040 
00041 // ROS console output for debugging
00042 #include <ros/console.h>
00043 
00044 uniserial::uniserial() :
00045   buffer_index_( 0 ), // set the buffer index at the head of the serial buffer.
00046   baud_rate_( 115200 ),
00047   num_bits_( 8 ),
00048   parity_( 0 ),
00049   num_stop_bits_( 1)
00050 {
00051   // ROS parameter for port name here!
00052   port_name_ == "/dev/ttyACM0";
00053 }
00054 
00055 uniserial::~uniserial()
00056 {
00057   close( file_descriptor_ );
00058 }
00059 
00060 bool uniserial::initialize( const std::string port_name, uint8_t num_bits, uint8_t parity, uint8_t num_stop_bits, uint16_t baud_rate )
00061 {
00062   struct termios options;
00063  
00064   port_name_ = port_name;
00065 
00066   ROS_INFO("uniserial::initialize(): Initializing on defined settings.");
00067   file_descriptor_ = open( port_name_.c_str(), O_RDWR | O_NOCTTY | O_NDELAY );
00068   if( file_descriptor_ == -1 )
00069   {
00070     ROS_ERROR("uniserial::initialize(): Unable to open port.");
00071     return false;
00072   }
00073     
00074   if( tcgetattr( file_descriptor_, &options ) < 0 )
00075   {
00076     ROS_ERROR("uniserial::initialize(): Couldn't get terminal attributes.");
00077     return false;
00078   }
00079     
00080   speed_t b_rate;
00081     
00082   switch( baud_rate_ )
00083   {
00084   case 4800:
00085     b_rate = B4800;
00086     break;
00087   case 9600:
00088     b_rate = B9600;
00089     break;
00090 #ifdef B14400
00091   case 14400:
00092     b_rate = B14400;
00093     break;
00094 #endif
00095   case 19200:
00096     b_rate = B19200;
00097     break;
00098 #ifdef B28800
00099   case 28800:
00100     b_rate = B28800;
00101     break;
00102 #endif
00103   case 38400:
00104     b_rate = B38400;
00105     break;
00106   case 57600:
00107     b_rate = B57600;
00108     break;
00109   case 115200:
00110     b_rate = B115200;
00111     break;
00112   default:
00113     b_rate = B115200;
00114   }
00115   cfsetispeed( &options, b_rate );
00116   cfsetospeed( &options, b_rate );
00117 
00118   // 8N1, the default Arduino Serial format: 8-bit, no parity, 1 stop bit.
00119   
00120   // Apply parity 
00121   switch( parity )
00122   {
00123   case 0:
00124     options.c_cflag &= ~PARENB; // no parity.
00125     break;
00126   case 1:
00127     options.c_cflag &= PARODD; // odd parity.
00128     break;
00129   case 2:
00130     options.c_cflag &= PARENB; // even parity (by default).
00131     break;
00132   default:
00133     options.c_cflag &= ~PARENB;
00134   }
00135   
00136   // Apply number of stop bits
00137   switch( num_stop_bits_ )
00138   {
00139   case 1:
00140     options.c_cflag &= ~CSTOPB;
00141     break;
00142   case 2:
00143     options.c_cflag &= CSTOPB;
00144     break;
00145   default:
00146     options.c_cflag &= ~CSTOPB;
00147   }
00148 
00149   // disable CSIZE
00150   options.c_cflag &= ~CSIZE;  
00151   switch( num_bits )
00152   {
00153   case 5:
00154     options.c_cflag |= CS5;
00155     break;
00156   case 6:
00157     options.c_cflag |= CS6;
00158     break;
00159   case 7:
00160     options.c_cflag |= CS7;
00161     break;
00162   case 8:
00163     options.c_cflag |= CS8;
00164     break;
00165   default:
00166     options.c_cflag |= CS8;
00167   }
00168   // disable flow control
00169   options.c_cflag &= ~CRTSCTS;
00170   
00171   // CREAD enables receiver.
00172   // CLOCAL ignores modem status lines.
00173   options.c_cflag |= CREAD | CLOCAL;
00174   // ~IXON disables start/stop output control.
00175   // ~IXOFF disables start/stop input control.
00176   // ~IXANY disables any character from restarting output
00177   options.c_iflag &= ~( IXON | IXOFF | IXANY ); 
00178   
00179   // ~ICANON disables canonical input and gives us acces to VMIN and VTIME
00180   // ~ECHO disables echo.
00181   // ~ECHOE disables other echoes.
00182   // ~ISIG disables signals.
00183   options.c_lflag &= ~( ICANON | ECHO | ECHOE | ISIG ); // make raw
00184   options.c_oflag &= ~OPOST; // make raw
00185 
00186   // see: http://unixwiz.net/techtips/termios-vmin-vtime.html
00187   options.c_cc[VMIN]  = 1; // when reading, VMIN is the minimum number of bytes that must arrive before the read function returns.
00188   options.c_cc[VTIME] = 0; // when reading, VTIME is the maximum interval between bytes in 0.1 second intervals. In this case we have 0.5 second delay between bytes max
00189     
00190   /* These next two lines may be system-dependent, 
00191    * in case it's openning a channel twice-in-a-row.
00192    * http://todbot.com/blog/2006/12/06/arduino-serial-c-code-to-talk-to-arduino/
00193    */
00194   //sleep(1); //Sleep time works only from 1 to 2 (2 not included)
00195   //tcflush(fd, TCIFLUSH);
00196     
00197   if( tcsetattr( file_descriptor_, TCSANOW, &options ) < 0 )
00198   {
00199     ROS_ERROR("init_serialport: Couldn't set serial port attributes.");
00200     return false;
00201   }
00202     
00203   // We must wait about 3 seconds for the Arduino to recover from a reboot upon initializing a serial connection.   
00204   ROS_INFO( "uniserial: Serial Port initialized." );
00205 
00206   return true;
00207 }
00208 
00209 bool uniserial::initialize()
00210 {
00211   return uniserial::initialize( port_name_, num_bits_, parity_, num_stop_bits_, baud_rate_ );
00212 }
00213 
00214 void uniserial::setPortName( const std::string p )
00215 {
00216   port_name_ = p;
00217 }
00218 
00219 
00220 uint8_t uniserial::Read()
00221 {
00222   int bytes_read;
00223   char temp_buffer;
00224   bytes_read = read( file_descriptor_, &temp_buffer, 1 );
00225   if( bytes_read < 0 )
00226   {
00227     ROS_ERROR( "Error reading!" );
00228     return 0;
00229   }
00230   return (uint8_t)temp_buffer;
00231 }
00232 
00233 
00234 bool uniserial::Write( uint8_t byte ) // writes a single byte to the serial device.
00235 {
00236   short bytes_written;
00237   char buff_to_write[1];
00238   buff_to_write[0] = byte;
00239  
00240   bytes_written = write( file_descriptor_, buff_to_write, 1 );
00241   if( bytes_written != 1 )
00242   {
00243     return false;
00244   }
00245   return true;
00246 }
00247 
00248 bool uniserial::Load_Byte( uint8_t byte )
00249 {
00250   // load  byte into current open index:
00251   Buffer[buffer_index_] = byte;
00252   buffer_index_++;
00253   return true;
00254 }
00255 
00256 
00257 int uniserial::Available()
00258 {
00259   int num_bytes;
00260   ioctl( file_descriptor_, FIONREAD, &num_bytes );
00261   return num_bytes;
00262 }
00263 
00264 bool uniserial::Flush()
00265 {
00266   int success = tcflush( file_descriptor_, TCIOFLUSH );
00267   if( success == 0 )
00268     return true;
00269   else
00270     return false;
00271 }
00272 
00273 bool uniserial::Read_Bytes( uint8_t num_bytes, uint8_t* storage_buffer )
00274 {
00275   int8_t bytes_read;
00276   bytes_read = read( file_descriptor_, storage_buffer, num_bytes );
00277   if( bytes_read != (int8_t)num_bytes )
00278     return false;
00279   else
00280     return true;
00281  
00282 }
00283 
00284 bool uniserial::Write_Bytes( uint8_t num_bytes, uint8_t* bytes_to_write )
00285 {
00286   if( num_bytes == 0 )
00287     return true;
00288   
00289   int8_t bytes_written;
00290   bytes_written = write( file_descriptor_, bytes_to_write, num_bytes );
00291   if( bytes_written != num_bytes )
00292     return false;
00293   else
00294     return true;
00295 }
00296 
00297 
00298  // // An example.  Reads 3 bytes, and writes the byte: 55 to the serial device.
00299  // int main()
00300  // {
00301  //   uniserial Serial;
00302  //   Serial.setPortName("/dev/ttyACM1");
00303  //   Serial.initialize();
00304  //   sleep(3);
00305  //   int val[3] = { Serial.Read(), Serial.Read(), Serial.Read() };
00306  //   bool write_status = Serial.Write(55);
00307  //   if( write_status == false )
00308  //   {
00309  //     cout << "writing failed." << endl;
00310  //   }
00311  //   cout << "I have read " << val[0]<<" "<< val[1] <<" " << val[2] << endl;
00312    
00313  //   sleep(1);
00314  //   return 0;
00315  // }


uniserial
Author(s): Joshua Vasquez and Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:49:03