serial_pos.hpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009  ** Ifdefs
00010  *****************************************************************************/
00011 
00012 #ifndef ECL_DEVICES_SERIAL_POS_HPP_
00013 #define ECL_DEVICES_SERIAL_POS_HPP_
00014 
00015 /*****************************************************************************
00016  ** Platform Check
00017  *****************************************************************************/
00018 
00019 #include <ecl/config.hpp>
00020 #if defined(ECL_IS_POSIX)
00021 
00022 /*****************************************************************************
00023  ** Includes
00024  *****************************************************************************/
00025 
00026 #include <string>
00027 #include <termios.h>
00028 #include <ecl/exceptions/standard_exception.hpp>
00029 #include <ecl/errors/compile_time_assert.hpp>
00030 #include <ecl/time/snooze.hpp>
00031 #include <ecl/utilities/parameter.hpp>
00032 #include <ecl/type_traits/fundamental_types.hpp>
00033 #include "detail/error_handler.hpp"
00034 #include "detail/exception_handler_pos.hpp"
00035 #include "serial_parameters.hpp"
00036 #include "traits.hpp"
00037 
00038 /*****************************************************************************
00039  ** Namespaces
00040  *****************************************************************************/
00041 
00042 namespace ecl
00043 {
00044 
00045   /*****************************************************************************
00046    ** Interface [Serial]
00047    *****************************************************************************/
00131   class Serial
00132   {
00133   public:
00134     /*********************
00135      ** C&D
00136      **********************/
00144     Serial() : is_open(false), error_handler(NoError)
00145     {};
00163     Serial(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
00164         const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity ) ecl_throw_decl(StandardException);
00165 
00171     virtual ~Serial();
00172 
00173     /*********************
00174      ** Open/Close
00175      **********************/
00210     bool open(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
00211         const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity ) ecl_throw_decl(StandardException);
00212 
00220     void close();
00230     bool open();
00231 
00232     /*********************
00233      ** Writing
00234      **********************/
00244     template <typename Byte>
00245     long write(const Byte &byte) ecl_debug_throw_decl(StandardException);
00246 
00257     template <typename Byte>
00258     long write(const Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException);
00259 
00266     void flush()
00267     {}
00268 
00269     /*********************
00270      ** Reading Modes
00271      **********************/
00290     void block(const unsigned long &timeout = 500);
00297     void unblock();
00298 
00299     /*********************
00300      ** Reading
00301      **********************/
00309     long remaining();
00323     template <typename Byte>
00324     long read(Byte &byte) ecl_debug_throw_decl(StandardException);
00339     template <typename Byte>
00340     long read(Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException);
00341 
00342     /*********************
00343      ** Serial Specific
00344      **********************/
00351     void clear()
00352     { tcflush(file_descriptor,TCIOFLUSH);}
00358     void clearInputBuffer()
00359     { tcflush(file_descriptor,TCIFLUSH);}
00365     void clearOutputBuffer()
00366     { tcflush(file_descriptor,TCOFLUSH);}
00367 
00374     const Error& error() const
00375     { return error_handler;}
00376   private:
00377     /*********************
00378      ** Constants
00379      **********************/
00380     enum {
00381       NonBlocking = -1
00382     };
00383     /*********************
00384      ** Variables
00385      **********************/
00386     int file_descriptor;
00387     termios options;
00388     std::string port;
00389     unsigned long read_timeout_ms;
00390     ecl::Snooze fake_snooze;
00391     unsigned int fake_loop_count;
00392     bool is_open;
00393     ecl::Error error_handler;
00394   };
00395 
00396   /*****************************************************************************
00397    ** Template Implementations
00398    *****************************************************************************/
00399 
00400   template <typename Byte>
00401   long Serial::write(const Byte &byte) ecl_debug_throw_decl(StandardException)
00402   {
00403     ecl_compile_time_assert( is_byte<Byte>::value );
00404     if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
00405     {
00406       ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00407       error_handler = OpenError;
00408       return -1;
00409     }
00410     ssize_t no_written = ::write(file_descriptor, &byte, 1);
00411     if ( no_written < 0 )
00412     {
00413       ecl_debug_throw(devices::write_exception(LOC));
00414       error_handler = devices::write_error();
00415       return -1;
00416     }
00417     error_handler = NoError;
00418     return no_written;
00419   }
00420 
00421   template <typename Byte>
00422   long Serial::write(const Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException)
00423   {
00424     ecl_compile_time_assert( is_byte<Byte>::value );
00425     if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
00426     {
00427       ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00428       error_handler = OpenError;
00429       return -1;
00430     }
00431     ssize_t no_written = ::write(file_descriptor, bytes, n);
00432     if ( no_written < 0 )
00433     {
00434       ecl_debug_throw(devices::write_exception(LOC));
00435       error_handler = devices::write_error();
00436       return -1;
00437     }
00438     error_handler = NoError;
00439     return no_written;
00440   }
00441 
00442   template <typename Byte>
00443   long Serial::read(Byte &byte) ecl_debug_throw_decl(StandardException)
00444   {
00445     ecl_compile_time_assert( is_byte<Byte>::value );
00446     if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
00447     {
00448       ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00449       error_handler = OpenError;
00450       return -1;
00451     }
00452     ssize_t no_read;
00453     if ( ( read_timeout_ms != NonBlocking ) && ( read_timeout_ms < 100 ) )
00454     {
00455       fake_snooze.initialise();
00456       for ( unsigned int i = 0; i < fake_loop_count; ++i )
00457       {
00458         no_read = ::read(file_descriptor, &byte, 1);
00459         if ( no_read != 0 )
00460         {
00461           break;
00462         }
00463         fake_snooze();
00464       }
00465     }
00466     else
00467     {
00468       no_read = ::read(file_descriptor, &byte, 1);
00469     }
00470     if ( no_read < 0 )
00471     {
00472       ecl_debug_throw(devices::read_exception(LOC));
00473       error_handler = devices::read_error();
00474       return -1;
00475     }
00476     error_handler = NoError;
00477     return no_read;
00478 
00479   }
00480 
00481   template <typename Byte>
00482   long Serial::read(Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException)
00483   {
00484     ecl_compile_time_assert( is_byte<Byte>::value );
00485     if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
00486     {
00487       ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00488       error_handler = OpenError;
00489       return -1;
00490     }
00491     ssize_t no_read = 0;
00492     if ( ( read_timeout_ms != NonBlocking ) && ( read_timeout_ms < 100 ) )
00493     {
00494       fake_snooze.initialise();
00495       for ( unsigned int i = 0; i < fake_loop_count; ++i )
00496       {
00497         no_read = ::read(file_descriptor, bytes, n);
00498         if ( no_read != 0 )
00499         {
00500           break;
00501         }
00502         fake_snooze();
00503       }
00504     }
00505     else
00506     {
00507       no_read = ::read(file_descriptor, bytes, n);
00508     }
00509     if ( no_read < 0 )
00510     {
00511       ecl_debug_throw(devices::read_exception(LOC));
00512       error_handler = devices::read_error();
00513       return -1;
00514     }
00515     error_handler = NoError;
00516     return no_read;
00517   }
00518 
00519   /*****************************************************************************
00520    ** Traits [Serial]
00521    *****************************************************************************/
00527   template <>
00528   class is_sink<Serial> : public True
00529   {};
00530 
00536   template <>
00537   class is_source<Serial> : public True
00538   {};
00539 
00545   template <>
00546   class is_sourcesink<Serial> : public True
00547   {};
00548 
00549 } // namespace ecl
00550 
00551 #endif /* ECL_IS_POSIX */
00552 #endif /* ECL_DEVICES_SERIAL_POS_HPP_ */


ecl_devices
Author(s): Daniel Stonier
autogenerated on Wed Aug 26 2015 11:27:37