Handles communication with and configuration of the mosaic (and beyond) receiver(s)
More...
#include <communication_core.hpp>
Handles communication with and configuration of the mosaic (and beyond) receiver(s)
Definition at line 102 of file communication_core.hpp.
◆ Comm_IO()
| io_comm_rx::Comm_IO::Comm_IO |
( |
| ) |
|
◆ ~Comm_IO()
| virtual io_comm_rx::Comm_IO::~Comm_IO |
( |
| ) |
|
|
virtualdefault |
Default destructor of the class Comm_IO.
◆ getHandlers()
◆ initializeSerial()
| bool io_comm_rx::Comm_IO::initializeSerial |
( |
std::string |
port, |
|
|
uint32_t |
baudrate = 115200, |
|
|
std::string |
flowcontrol = "None" |
|
) |
| |
Initializes the serial port.
- Parameters
-
| [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)) |
- Returns
- True if connection could be established, false otherwise
Definition at line 101 of file communication_core.cpp.
◆ initializeTCP()
| bool io_comm_rx::Comm_IO::initializeTCP |
( |
std::string |
host, |
|
|
std::string |
port |
|
) |
| |
Initializes the TCP I/O.
- Parameters
-
| [in] | host | The TCP host |
| [in] | port | The TCP port |
- Returns
- True if connection could be established, false otherwise
Definition at line 47 of file communication_core.cpp.
◆ resetSerial()
| void io_comm_rx::Comm_IO::resetSerial |
( |
std::string |
port | ) |
|
Reset the Serial I/O port, e.g. after a Rx reset.
- Parameters
-
| [in] | port | The device's port address |
Definition at line 249 of file communication_core.cpp.
◆ send()
| void io_comm_rx::Comm_IO::send |
( |
std::string |
cmd | ) |
|
◆ setManager()
◆ CallbackHandlers
◆ RxMessage
◆ baudrate_
| uint32_t io_comm_rx::Comm_IO::baudrate_ |
|
private |
◆ handlers_
◆ host_
| std::string io_comm_rx::Comm_IO::host_ |
|
private |
◆ manager_
Processes I/O stream data This declaration is deliberately stream-independent (Serial or TCP).
Definition at line 160 of file communication_core.hpp.
◆ port_
| std::string io_comm_rx::Comm_IO::port_ |
|
private |
◆ serial_port_
| std::string io_comm_rx::Comm_IO::serial_port_ |
|
private |
◆ SET_BAUDRATE_SLEEP_
| const unsigned int io_comm_rx::Comm_IO::SET_BAUDRATE_SLEEP_ = 500000 |
|
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.
The documentation for this class was generated from the following files: