Program Listing for File Serial.h

Return to documentation for file (/tmp/ws/src/schunk_svh_library/include/schunk_svh_library/serial/Serial.h)

//
// © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
// © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
//
// This file is part of the Schunk SVH Library.
//
// The Schunk SVH Library is free software: you can redistribute it and/or
// modify it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or (at your
// option) any later version.
//
// The Schunk SVH Library is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
// Public License for more details.
//
// You should have received a copy of the GNU General Public License along with
// the Schunk SVH Library. If not, see <https://www.gnu.org/licenses/>.
//

//----------------------------------------------------------------------
//----------------------------------------------------------------------
#ifndef DRIVER_SVH_SERIAL_SERIAL_H_INCLUDED
#define DRIVER_SVH_SERIAL_SERIAL_H_INCLUDED

#include <string>
#include <sys/types.h>

#include "schunk_svh_library/ImportExport.h"
#include "schunk_svh_library/serial/SerialFlags.h"

#ifdef _SYSTEM_WIN32_
typedef unsigned int speed_t;
typedef int ssize_t;
#endif

#ifdef _SYSTEM_POSIX_
#  include <unistd.h>
#  ifdef _SYSTEM_DARWIN_
#    include <termios.h>
#  else
#    include <termio.h>
#  endif
#endif

namespace driver_svh {
namespace serial {


class DRIVER_SVH_IMPORT_EXPORT Serial
{
public:
  Serial(const char* dev_name, const SerialFlags& flags);

  Serial(const char* dev_name, SerialFlags::BaudRate baud_rate, const SerialFlags& flags);

  ~Serial();
  int changeBaudrate(SerialFlags::BaudRate speed);

  int clearReceiveBuffer();

  int clearSendBuffer();

  bool open(const SerialFlags& flags)
  {
    m_serial_flags = flags;
    return open();
  }

  bool open();

  bool isOpen() const;

  void close();


  ssize_t write(const void* data, ssize_t size);
  ssize_t read(void* data, ssize_t size, unsigned long time = 100, bool return_on_less_data = true);
  int status() const { return m_status; }

  std::string statusText() const;

  const char* deviceName() const { return m_dev_name; }

  int fileDescriptor()
  {
#ifdef _SYSTEM_POSIX_
    return m_file_descr;
#else
    return 0;
#endif
  }

private:
  // Forbid copying.
  Serial(const Serial&);
  Serial& operator=(const Serial&);

  void dumpData(void* data, size_t length);

#ifdef _SYSTEM_WIN32_
  HANDLE m_com;
  unsigned char m_read_buffer[0x4000];
  ssize_t m_read_buffer_fill;
#endif

#ifdef _SYSTEM_POSIX_
  int m_file_descr;
  termios m_io_set_old;
#endif

  char* m_dev_name;
  SerialFlags m_serial_flags;
  int m_status;
};

} // namespace serial
} // namespace driver_svh

#endif