Program Listing for File serial_pos.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_devices/include/ecl/devices/serial_pos.hpp)

/*****************************************************************************
 ** Ifdefs
 *****************************************************************************/

#ifndef ECL_DEVICES_SERIAL_POS_HPP_
#define ECL_DEVICES_SERIAL_POS_HPP_

/*****************************************************************************
 ** Platform Check
 *****************************************************************************/

#include <ecl/config.hpp>
#if defined(ECL_IS_POSIX)

/*****************************************************************************
 ** Includes
 *****************************************************************************/

#include <string>
#include <termios.h>
#include <ecl/exceptions/standard_exception.hpp>
#include <ecl/errors/compile_time_assert.hpp>
#include <ecl/time/snooze.hpp>
#include <ecl/utilities/parameter.hpp>
#include <ecl/type_traits/fundamental_types.hpp>
#include "detail/error_handler.hpp"
#include "detail/exception_handler_pos.hpp"
#include "serial_parameters.hpp"
#include "traits.hpp"

/*****************************************************************************
 ** Namespaces
 *****************************************************************************/

namespace ecl
{

  /*****************************************************************************
   ** Interface [Serial]
   *****************************************************************************/
  class Serial
  {
  public:
    /*********************
     ** C&D
     **********************/
    Serial() : is_open(false), error_handler(NoError)
    {};
    Serial(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
        const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity );

    virtual ~Serial();

    /*********************
     ** Open/Close
     **********************/
    bool open(const std::string& port_name, const BaudRate &baud_rate = BaudRate_115200, const DataBits &data_bits = DataBits_8,
        const StopBits &stop_bits = StopBits_1, const Parity &parity = NoParity );

    void close();
    bool open();

    /*********************
     ** Writing
     **********************/
    template <typename Byte>
    long write(const Byte &byte);

    template <typename Byte>
    long write(const Byte *bytes, const unsigned long &n);

    void flush()
    {}

    /*********************
     ** Reading Modes
     **********************/
    void block(const unsigned long &timeout = 500);
    void unblock();

    /*********************
     ** Reading
     **********************/
    long remaining();
    template <typename Byte>
    long read(Byte &byte);
    template <typename Byte>
    long read(Byte *bytes, const unsigned long &n);

    /*********************
     ** Serial Specific
     **********************/
    void clear()
    { tcflush(file_descriptor,TCIOFLUSH);}
    void clearInputBuffer()
    { tcflush(file_descriptor,TCIFLUSH);}
    void clearOutputBuffer()
    { tcflush(file_descriptor,TCOFLUSH);}

    const Error& error() const
    { return error_handler;}
  private:
    /*********************
     ** Constants
     **********************/
    enum {
      NonBlocking = -1
    };
    /*********************
     ** Variables
     **********************/
    int file_descriptor;
    termios options;
    std::string port;
    long read_timeout_ms;
    ecl::Snooze fake_snooze;
    unsigned int fake_loop_count;
    bool is_open;
    ecl::Error error_handler;
  };

  /*****************************************************************************
   ** Template Implementations
   *****************************************************************************/

  template <typename Byte>
  long Serial::write(const Byte &byte)
  {
    ecl_compile_time_assert( is_byte<Byte>::value );
    if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
    {
      ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
      error_handler = OpenError;
      return -1;
    }
    ssize_t no_written = ::write(file_descriptor, &byte, 1);
    if ( no_written < 0 )
    {
      ecl_debug_throw(devices::write_exception(LOC));
      error_handler = devices::write_error();
      return -1;
    }
    error_handler = NoError;
    return no_written;
  }

  template <typename Byte>
  long Serial::write(const Byte *bytes, const unsigned long &n)
  {
    ecl_compile_time_assert( is_byte<Byte>::value );
    if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
    {
      ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
      error_handler = OpenError;
      return -1;
    }
    ssize_t no_written = ::write(file_descriptor, bytes, n);
    if ( no_written < 0 )
    {
      ecl_debug_throw(devices::write_exception(LOC));
      error_handler = devices::write_error();
      return -1;
    }
    error_handler = NoError;
    return no_written;
  }

  template <typename Byte>
  long Serial::read(Byte &byte)
  {
    ecl_compile_time_assert( is_byte<Byte>::value );
    if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
    {
      ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
      error_handler = OpenError;
      return -1;
    }
    ssize_t no_read;
    if ( ( read_timeout_ms != NonBlocking ) && ( read_timeout_ms < 100 ) )
    {
      fake_snooze.initialise();
      for ( unsigned int i = 0; i < fake_loop_count; ++i )
      {
        no_read = ::read(file_descriptor, &byte, 1);
        if ( no_read != 0 )
        {
          break;
        }
        fake_snooze();
      }
    }
    else
    {
      no_read = ::read(file_descriptor, &byte, 1);
    }
    if ( no_read < 0 )
    {
      ecl_debug_throw(devices::read_exception(LOC));
      error_handler = devices::read_error();
      return -1;
    }
    error_handler = NoError;
    return no_read;

  }

  template <typename Byte>
  long Serial::read(Byte *bytes, const unsigned long &n)
  {
    ecl_compile_time_assert( is_byte<Byte>::value );
    if ( !is_open )  // internal check only, don't worry about doing the full device filename check here (we need speed)
    {
      ecl_debug_throw( StandardException(LOC, OpenError, std::string("Port ") + port + std::string(" is not open.")));
      error_handler = OpenError;
      return -1;
    }
    ssize_t no_read = 0;
    if ( ( read_timeout_ms != NonBlocking ) && ( read_timeout_ms < 100 ) )
    {
      fake_snooze.initialise();
      for ( unsigned int i = 0; i < fake_loop_count; ++i )
      {
        no_read = ::read(file_descriptor, bytes, n);
        if ( no_read != 0 )
        {
          break;
        }
        fake_snooze();
      }
    }
    else
    {
      no_read = ::read(file_descriptor, bytes, n);
    }
    if ( no_read < 0 )
    {
      ecl_debug_throw(devices::read_exception(LOC));
      error_handler = devices::read_error();
      return -1;
    }
    error_handler = NoError;
    return no_read;
  }

  /*****************************************************************************
   ** Traits [Serial]
   *****************************************************************************/
  template <>
  class is_sink<Serial> : public True
  {};

  template <>
  class is_source<Serial> : public True
  {};

  template <>
  class is_sourcesink<Serial> : public True
  {};

} // namespace ecl

#endif /* ECL_IS_POSIX */
#endif /* ECL_DEVICES_SERIAL_POS_HPP_ */