Public Member Functions | Private Member Functions | Private Attributes | List of all members
driver_svh::serial::Serial Class Reference

Enables acces to serial devices. More...

#include <Serial.h>

Public Member Functions

int changeBaudrate (SerialFlags::BaudRate speed)
 
int clearReceiveBuffer ()
 
int clearSendBuffer ()
 
void close ()
 
const char * deviceName () const
 
int fileDescriptor ()
 
bool isOpen () const
 
bool open ()
 
bool open (const SerialFlags &flags)
 
ssize_t read (void *data, ssize_t size, unsigned long time=100, bool return_on_less_data=true)
 
 Serial (const char *dev_name, const SerialFlags &flags)
 
 Serial (const char *dev_name, SerialFlags::BaudRate baud_rate, const SerialFlags &flags)
 
int status () const
 
std::string statusText () const
 
ssize_t write (const void *data, ssize_t size)
 
 ~Serial ()
 

Private Member Functions

void dumpData (void *data, size_t length)
 
Serialoperator= (const Serial &)
 
 Serial (const Serial &)
 

Private Attributes

char * m_dev_name
 
SerialFlags m_serial_flags
 
int m_status
 

Detailed Description

Enables acces to serial devices.

Open a serial device, change baudrates, read from and write to the device. Status-information after calling the functions get be

Definition at line 68 of file Serial.h.

Constructor & Destructor Documentation

◆ Serial() [1/3]

driver_svh::serial::Serial::Serial ( const char *  dev_name,
const SerialFlags flags 
)

Opens the device (if possible) with the given flags.

Parameters
flagscan be values of the following values ORed together
  • CS5, CS6, CS7, or CS8 databits
  • CSTOPB set two stop bits, rather than one.
  • CREAD enable receiver.
  • PARENB enable parity generation on output and parity checking for input.
  • PARODD parity for input and output is odd.
  • HUPCL lower modem control lines after last process closes the device (hang up).
  • CLOCAL ignore modem control lines
  • B50, B75, B110, B134, B150, B200, B300, B600, B1200, B1800, B2400, B4800, B9600, B19200, B38400, B57600, B115200, B230400, B921600 Baudrates
  • CRTSCTS flow control.

Definition at line 70 of file Serial.cpp.

◆ Serial() [2/3]

driver_svh::serial::Serial::Serial ( const char *  dev_name,
SerialFlags::BaudRate  baud_rate,
const SerialFlags flags 
)

This is an overloaded constructor, provided for convenience. buad_rate overwrites the baud rate set in flags.

Definition at line 83 of file Serial.cpp.

◆ ~Serial()

driver_svh::serial::Serial::~Serial ( )

Restore old serial settings and close device

Definition at line 804 of file Serial.cpp.

◆ Serial() [3/3]

driver_svh::serial::Serial::Serial ( const Serial )
private

Member Function Documentation

◆ changeBaudrate()

int driver_svh::serial::Serial::changeBaudrate ( SerialFlags::BaudRate  speed)

speed is one of the followind values :

  • B50, B75, B110, B134, B150, B200, B300, B600, B1200, B1800, B2400, B4800, B9600, B19200, B38400, B57600, B115200, B230400, B921600 Returns 0 on success. Returns -status on failure.

Definition at line 260 of file Serial.cpp.

◆ clearReceiveBuffer()

int driver_svh::serial::Serial::clearReceiveBuffer ( )

Clears the serial port's receive buffer.

Definition at line 370 of file Serial.cpp.

◆ clearSendBuffer()

int driver_svh::serial::Serial::clearSendBuffer ( )

Clears the serial port's send buffer.

Definition at line 403 of file Serial.cpp.

◆ close()

void driver_svh::serial::Serial::close ( )

Close the serial interface.

Definition at line 759 of file Serial.cpp.

◆ deviceName()

const char* driver_svh::serial::Serial::deviceName ( ) const
inline

Definition at line 170 of file Serial.h.

◆ dumpData()

void driver_svh::serial::Serial::dumpData ( void *  data,
size_t  length 
)
private

Definition at line 249 of file Serial.cpp.

◆ fileDescriptor()

int driver_svh::serial::Serial::fileDescriptor ( )
inline

Return the file descriptor of the serial class

Definition at line 175 of file Serial.h.

◆ isOpen()

bool driver_svh::serial::Serial::isOpen ( ) const

Returns true if the serial interface is opened. false otherwhise.

Definition at line 748 of file Serial.cpp.

◆ open() [1/2]

bool driver_svh::serial::Serial::open ( )

Opens the serial interface.

Definition at line 97 of file Serial.cpp.

◆ open() [2/2]

bool driver_svh::serial::Serial::open ( const SerialFlags flags)
inline

Opens the serial interface with the given flags

Definition at line 123 of file Serial.h.

◆ operator=()

Serial& driver_svh::serial::Serial::operator= ( const Serial )
private

◆ read()

ssize_t driver_svh::serial::Serial::read ( void *  data,
ssize_t  size,
unsigned long  time = 100,
bool  return_on_less_data = true 
)

Read data from device. This function waits until

Parameters
timeus passed or the respected number of bytes are received via serial line. if (
return_on_less_datais true (default value), the number of bytes that have been receives are returned and the data is stored in
data.If the parameter is false, data is only read from serial line, if at least
sizebytes are available.

Definition at line 492 of file Serial.cpp.

◆ status()

int driver_svh::serial::Serial::status ( ) const
inline

All routines return a negavtiv number on error. Then the global errno is stored into a private variable. Use this funtion to ask for this value. Especially the constructor cannot return an error-value. Check the succesful opening of the device by calling this function. It returns 0, if no error occured.

Definition at line 166 of file Serial.h.

◆ statusText()

std::string driver_svh::serial::Serial::statusText ( ) const

Definition at line 718 of file Serial.cpp.

◆ write()

ssize_t driver_svh::serial::Serial::write ( const void *  data,
ssize_t  size 
)

Write data to serial out.

Definition at line 436 of file Serial.cpp.

Member Data Documentation

◆ m_dev_name

char* driver_svh::serial::Serial::m_dev_name
private

Definition at line 202 of file Serial.h.

◆ m_serial_flags

SerialFlags driver_svh::serial::Serial::m_serial_flags
private

Definition at line 203 of file Serial.h.

◆ m_status

int driver_svh::serial::Serial::m_status
private

Definition at line 204 of file Serial.h.


The documentation for this class was generated from the following files:


schunk_svh_library
Author(s): Georg Heppner, Lars Pfotzer, Felix Exner, Johannes Mangler, Stefan Scherzinger, Pascal Becker
autogenerated on Fri Apr 14 2023 02:53:52