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
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include "uniserial/uniserial.hpp"
00040
00041
00042 #include <ros/console.h>
00043
00044 uniserial::uniserial() :
00045 buffer_index_( 0 ),
00046 baud_rate_( 115200 ),
00047 num_bits_( 8 ),
00048 parity_( 0 ),
00049 num_stop_bits_( 1)
00050 {
00051
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
00119
00120
00121 switch( parity )
00122 {
00123 case 0:
00124 options.c_cflag &= ~PARENB;
00125 break;
00126 case 1:
00127 options.c_cflag &= PARODD;
00128 break;
00129 case 2:
00130 options.c_cflag &= PARENB;
00131 break;
00132 default:
00133 options.c_cflag &= ~PARENB;
00134 }
00135
00136
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
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
00169 options.c_cflag &= ~CRTSCTS;
00170
00171
00172
00173 options.c_cflag |= CREAD | CLOCAL;
00174
00175
00176
00177 options.c_iflag &= ~( IXON | IXOFF | IXANY );
00178
00179
00180
00181
00182
00183 options.c_lflag &= ~( ICANON | ECHO | ECHOE | ISIG );
00184 options.c_oflag &= ~OPOST;
00185
00186
00187 options.c_cc[VMIN] = 1;
00188 options.c_cc[VTIME] = 0;
00189
00190
00191
00192
00193
00194
00195
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
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 )
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
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
00299
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315