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_pos.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 ** Interface [Serial]
00046 *****************************************************************************/
00130 class Serial {
00131 public:
00132         /*********************
00133         ** C&D
00134         **********************/
00142         Serial() : is_open(false), error_handler(NoError) {};
00160         Serial(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
00161                         const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity ) ecl_throw_decl(StandardException);
00162 
00168         virtual ~Serial();
00169 
00170         /*********************
00171         ** Open/Close
00172         **********************/
00204         bool open(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
00205                         const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity )  ecl_throw_decl(StandardException);
00206 
00214         void close();
00220         bool open() const { return is_open; }
00221 
00222         /*********************
00223         ** Writing
00224         **********************/
00234         template <typename Byte>
00235         long write(const Byte &byte) ecl_debug_throw_decl(StandardException);
00236 
00247         template <typename Byte>
00248         long write(const Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException);
00249 
00256         void flush() {}
00257 
00258         /*********************
00259         ** Reading Modes
00260         **********************/
00279         void block(const unsigned long &timeout = 500);
00286         void unblock();
00287 
00288         /*********************
00289         ** Reading
00290         **********************/
00298         long remaining();
00312         template <typename Byte>
00313     long read(Byte &byte) ecl_debug_throw_decl(StandardException);
00328         template <typename Byte>
00329     long read(Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException);
00330 
00331     /*********************
00332         ** Serial Specific
00333         **********************/
00340     void clear() { tcflush(file_descriptor,TCIOFLUSH); }
00346     void clearInputBuffer() { tcflush(file_descriptor,TCIFLUSH); }
00352     void clearOutputBuffer() { tcflush(file_descriptor,TCOFLUSH); }
00353 
00360     const Error& error() const { return error_handler; }
00361 private:
00362         /*********************
00363         ** Variables
00364         **********************/
00365         int file_descriptor;
00366     termios options;
00367     std::string port;
00368     unsigned long read_timeout_ms;
00369     ecl::Snooze fake_snooze;
00370     unsigned int fake_loop_count;
00371     bool is_open;
00372     ecl::Error error_handler;
00373 };
00374 
00375 /*****************************************************************************
00376 ** Template Implementations
00377 *****************************************************************************/
00378 
00379 template <typename Byte>
00380 long Serial::write(const Byte &byte) ecl_debug_throw_decl(StandardException) {
00381     ecl_compile_time_assert( is_byte<Byte>::value );
00382     if ( !open() ) {
00383         ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00384         error_handler = OpenError;
00385         return -1;
00386     }
00387         ssize_t no_written = ::write(file_descriptor, &byte, 1);
00388         if ( no_written < 0 ) {
00389                 ecl_debug_throw(devices::write_exception(LOC));
00390                 error_handler = devices::write_error();
00391                 return -1;
00392         }
00393     error_handler = NoError;
00394         return no_written;
00395 }
00396 
00397 template <typename Byte>
00398 long Serial::write(const Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException) {
00399     ecl_compile_time_assert( is_byte<Byte>::value );
00400     if ( !open() ) {
00401         ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00402         error_handler = OpenError;
00403         return -1;
00404     }
00405         ssize_t no_written = ::write(file_descriptor, bytes, n);
00406         if ( no_written < 0 ) {
00407                 ecl_debug_throw(devices::write_exception(LOC));
00408                 error_handler = devices::write_error();
00409                 return -1;
00410         }
00411     error_handler = NoError;
00412         return no_written;
00413 }
00414 
00415 template <typename Byte>
00416 long Serial::read(Byte &byte) ecl_debug_throw_decl(StandardException) {
00417     ecl_compile_time_assert( is_byte<Byte>::value );
00418     if ( !open() ) {
00419         ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00420         error_handler = OpenError;
00421         return -1;
00422     }
00423     ssize_t no_read;
00424     if ( read_timeout_ms < 100 ) {
00425         fake_snooze.initialise();
00426         for ( unsigned int i = 0; i < fake_loop_count; ++i ) {
00427                 no_read = ::read(file_descriptor, &byte, 1);
00428                 if ( no_read != 0 ) {
00429                         break;
00430                 }
00431                 fake_snooze();
00432         }
00433     } else {
00434         no_read = ::read(file_descriptor, &byte, 1);
00435     }
00436         if ( no_read < 0 ) {
00437                 ecl_debug_throw(devices::read_exception(LOC));
00438                 error_handler = devices::read_error();
00439                 return -1;
00440         }
00441     error_handler = NoError;
00442         return no_read;
00443 
00444 }
00445 
00446 template <typename Byte>
00447 long Serial::read(Byte *bytes, const unsigned long &n) ecl_debug_throw_decl(StandardException) {
00448     ecl_compile_time_assert( is_byte<Byte>::value );
00449     if ( !open() ) {
00450         ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
00451         error_handler = OpenError;
00452         return -1;
00453     }
00454     ssize_t no_read = 0;
00455     if ( read_timeout_ms < 100 ) {
00456         fake_snooze.initialise();
00457         for ( unsigned int i = 0; i < fake_loop_count; ++i ) {
00458                 no_read = ::read(file_descriptor, bytes, n);
00459                 if ( no_read != 0 ) {
00460                         break;
00461                 }
00462                 fake_snooze();
00463         }
00464     } else {
00465         no_read = ::read(file_descriptor, bytes, n);
00466     }
00467         if ( no_read < 0 ) {
00468                 ecl_debug_throw(devices::read_exception(LOC));
00469                 error_handler = devices::read_error();
00470                 return -1;
00471         }
00472     error_handler = NoError;
00473         return no_read;
00474 }
00475 
00476 /*****************************************************************************
00477 ** Traits [Serial]
00478 *****************************************************************************/
00484 template <>
00485 class is_sink<Serial> : public True {};
00486 
00492 template <>
00493 class is_source<Serial> : public True {};
00494 
00500 template <>
00501 class is_sourcesink<Serial> : public True {};
00502 
00503 
00504 } // namespace ecl
00505 
00506 #endif /* ECL_IS_POSIX */
00507 #endif /* ECL_DEVICES_SERIAL_POS_HPP_ */


ecl_devices
Author(s): Daniel Stonier (d.stonier@gmail.com)
autogenerated on Thu Jan 2 2014 11:12:50