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 |
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.
toposens_driver::Serial::Serial | ( | std::string | port | ) |
Opens a persistent serial connection at the given port.
port | Device 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.
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.
void toposens_driver::Serial::getFrame | ( | std::stringstream & | data | ) |
Extracts a single TS data frame into the given iostream.
data | Points 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.
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'
frame | string received from sensor |
Checks whether a frame is an acknowledgement for a paramter value.
Definition at line 190 of file serial.cpp.
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.
cmd | Instance of command class specifying a parameter to be updated and the desired value. |
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.
bool toposens_driver::Serial::waitForAcknowledgement | ( | std::stringstream & | buffer | ) |
Blocks execution of driver until an acknowledgement message is received or watchdog timer expires.
buffer | stringstream to be used for messaging |
Blocks execution of driver until an acknowledgement message is received or watchdog timer expires.
Definition at line 203 of file serial.cpp.
|
private |
|
private |
|
private |