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

Provides low-level I/O access to TS data stream using native Unix API. More...

#include <serial.h>

Public Member Functions

void getFrame (std::stringstream &data)
 
bool isAcknowledgementFrame (std::string frame)
 
void sendCmd (Command cmd, std::stringstream &data)
 
 Serial (std::string port)
 
bool waitForAcknowledgement (std::stringstream &buffer)
 
 ~Serial ()
 

Private Attributes

int _fd
 
std::string _port
 
const unsigned int kBaud = B576000
 

Detailed Description

Provides low-level I/O access to TS data stream using native Unix API.

Sets up a UART bridge to access raw data packets from a TS device. Maintains simple read-write access at the given baud rate. Methods defined here are independent of ROS.

Definition at line 23 of file serial.h.

Constructor & Destructor Documentation

◆ Serial()

toposens_driver::Serial::Serial ( std::string  port)

Opens a persistent serial connection at the given port.

Parameters
portDevice endpoint usually of the form /dev/ttyUSB*.

Various termios struct flags are optimized for a connection that works best with the TS firmware. Any intrinsic flow control or bit processing is disabled.

Connection is a non-blocking thread that returns when at least 1 byte is received or 0.1s has passed since the last read operation.

Definition at line 22 of file serial.cpp.

◆ ~Serial()

toposens_driver::Serial::~Serial ( void  )

Flushes out bits from the serial pipe and closes its corresponding linux file descriptor.

Definition at line 108 of file serial.cpp.

Member Function Documentation

◆ getFrame()

void toposens_driver::Serial::getFrame ( std::stringstream &  data)

Extracts a single TS data frame into the given iostream.

Parameters
dataPoints to a string stream expecting a sensor frame.

Reads incoming bytes to the string stream pointer till the firmware-defined frame terminator 'E' is reached. Returns if no data has been received for 1 second.

Definition at line 127 of file serial.cpp.

◆ isAcknowledgementFrame()

bool toposens_driver::Serial::isAcknowledgementFrame ( std::string  frame)

Checks whether frame string is an acknowledgement message.

An acknowledgement frame corresponds to a single parameter update and has the following format:
- Starts with char 'S'
- 6 bytes of bit shifts to decode parameter level as defined in Command::Parameters, '-1' denotes unknown parameter
- Char 'C', indicates a command acknowledgement frame
- 5 bytes of firmware parameter value
- Ends with char 'E'

Parameters
framestring received from sensor
Returns
true if acknowledgement is received, false if watchdog terminated blocking mode

Checks whether a frame is an acknowledgement for a paramter value.

Definition at line 190 of file serial.cpp.

◆ sendCmd()

void toposens_driver::Serial::sendCmd ( Command  cmd,
std::stringstream &  data 
)

Writes the given bytes to the serial stream and confirms a parameter update. Usually used for updating sensor settings during runtime.

Parameters
cmdInstance of command class specifying a parameter to be updated and the desired value.
Returns
True if sensor handshake is received to confirm settings update, false otherwise.

Note that this returns true as long as data is written to the serial stream without error and a response is received.

Definition at line 157 of file serial.cpp.

◆ waitForAcknowledgement()

bool toposens_driver::Serial::waitForAcknowledgement ( std::stringstream &  buffer)

Blocks execution of driver until an acknowledgement message is received or watchdog timer expires.

Parameters
bufferstringstream to be used for messaging
Returns
true if acknowledgement is received, false if watchdog terminated blocking mode

Blocks execution of driver until an acknowledgement message is received or watchdog timer expires.

Definition at line 203 of file serial.cpp.

Member Data Documentation

◆ _fd

int toposens_driver::Serial::_fd
private

Linux file descriptor pointing to TS device port.

Definition at line 77 of file serial.h.

◆ _port

std::string toposens_driver::Serial::_port
private

Stored device port for future access.

Definition at line 78 of file serial.h.

◆ kBaud

const unsigned int toposens_driver::Serial::kBaud = B576000
private

Baud rate needed for TS device comms.

Definition at line 79 of file serial.h.


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


toposens_driver
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Roua Mokchah, Nancy Seckel, Georgiana Barbut
autogenerated on Mon Feb 28 2022 23:57:40