ROSaic
|
Handles communication with and configuration of the mosaic (and beyond) receiver(s) More...
#include <communication_core.hpp>
Public Member Functions | |
Comm_IO () | |
Default constructor of the class Comm_IO. More... | |
virtual | ~Comm_IO ()=default |
Default destructor of the class Comm_IO. More... | |
bool | initializeSerial (std::string port, uint32_t baudrate=115200, std::string flowcontrol="None") |
Initializes the serial port. More... | |
bool | initializeTCP (std::string host, std::string port) |
Initializes the TCP I/O. More... | |
void | setManager (const boost::shared_ptr< Manager > &manager) |
Set the I/O manager. More... | |
void | resetSerial (std::string port) |
Reset the Serial I/O port, e.g. after a Rx reset. More... | |
CallbackHandlers | getHandlers () const |
void | send (std::string cmd) |
Data Fields | |
CallbackHandlers | handlers_ |
Callback handlers for the inwards streaming messages. More... | |
Private Attributes | |
std::string | serial_port_ |
Saves the port description. More... | |
boost::shared_ptr< Manager > | manager_ |
uint32_t | baudrate_ |
Baudrate at the moment, unless InitializeSerial or ResetSerial fail. More... | |
std::string | host_ |
Host currently connected to. More... | |
std::string | port_ |
Port over which TCP/IP connection is currently established. More... | |
Static Private Attributes | |
static const unsigned int | SET_BAUDRATE_SLEEP_ = 500000 |
Friends | |
class | CallbackHandlers |
class | RxMessage |
Handles communication with and configuration of the mosaic (and beyond) receiver(s)
Definition at line 102 of file communication_core.hpp.
io_comm_rx::Comm_IO::Comm_IO | ( | ) |
Default constructor of the class Comm_IO.
Definition at line 39 of file communication_core.cpp.
|
virtualdefault |
Default destructor of the class Comm_IO.
|
inline |
Definition at line 147 of file communication_core.hpp.
References handlers_, and send().
Referenced by rosaic_node::ROSaicNode::defineMessages().
bool io_comm_rx::Comm_IO::initializeSerial | ( | std::string | port, |
uint32_t | baudrate = 115200 , |
||
std::string | flowcontrol = "None" |
||
) |
Initializes the serial port.
[in] | port | The device's port address |
[in] | baudrate | The chosen baud rate of the port |
[in] | flowcontrol | Default is "None", set variable (not yet checked) to "RTS|CTS" to activate hardware flow control (only for serial ports COM1, COM2 and COM3 (for mosaic)) |
Definition at line 101 of file communication_core.cpp.
References baudrate_, io_comm_rx::BAUDRATES, manager_, serial_port_, SET_BAUDRATE_SLEEP_, and setManager().
Referenced by rosaic_node::ROSaicNode::reconnect().
bool io_comm_rx::Comm_IO::initializeTCP | ( | std::string | host, |
std::string | port | ||
) |
Initializes the TCP I/O.
[in] | host | The TCP host |
[in] | port | The TCP port |
Definition at line 47 of file communication_core.cpp.
References host_, manager_, port_, and setManager().
Referenced by rosaic_node::ROSaicNode::reconnect().
void io_comm_rx::Comm_IO::resetSerial | ( | std::string | port | ) |
Reset the Serial I/O port, e.g. after a Rx reset.
[in] | port | The device's port address |
Definition at line 249 of file communication_core.cpp.
References baudrate_, manager_, serial_port_, and setManager().
void io_comm_rx::Comm_IO::send | ( | std::string | cmd | ) |
Definition at line 41 of file communication_core.cpp.
References manager_.
Referenced by rosaic_node::ROSaicNode::configureRx(), and getHandlers().
void io_comm_rx::Comm_IO::setManager | ( | const boost::shared_ptr< Manager > & | manager | ) |
Set the I/O manager.
[in] | manager | An I/O handler |
Definition at line 240 of file communication_core.cpp.
References handlers_, manager_, and io_comm_rx::CallbackHandlers::readCallback().
Referenced by initializeSerial(), initializeTCP(), and resetSerial().
|
friend |
Definition at line 164 of file communication_core.hpp.
|
friend |
Definition at line 165 of file communication_core.hpp.
|
private |
Baudrate at the moment, unless InitializeSerial or ResetSerial fail.
Definition at line 162 of file communication_core.hpp.
Referenced by initializeSerial(), and resetSerial().
CallbackHandlers io_comm_rx::Comm_IO::handlers_ |
Callback handlers for the inwards streaming messages.
Definition at line 152 of file communication_core.hpp.
Referenced by rosaic_node::ROSaicNode::defineMessages(), getHandlers(), and setManager().
|
private |
Host currently connected to.
Definition at line 168 of file communication_core.hpp.
Referenced by initializeTCP().
|
private |
Processes I/O stream data This declaration is deliberately stream-independent (Serial or TCP).
Definition at line 160 of file communication_core.hpp.
Referenced by initializeSerial(), initializeTCP(), resetSerial(), send(), and setManager().
|
private |
Port over which TCP/IP connection is currently established.
Definition at line 170 of file communication_core.hpp.
Referenced by initializeTCP().
|
private |
Saves the port description.
Definition at line 157 of file communication_core.hpp.
Referenced by initializeSerial(), and resetSerial().
|
staticprivate |
Sleep time in microseconds (there is no Unix command for milliseconds) after setting the baudrate to certain value (important between increments)
Definition at line 173 of file communication_core.hpp.
Referenced by initializeSerial().