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 106 of file communication_core.hpp.
◆ Comm_IO()
◆ ~Comm_IO()
io_comm_rx::Comm_IO::~Comm_IO |
( |
| ) |
|
◆ configureRx()
void io_comm_rx::Comm_IO::configureRx |
( |
| ) |
|
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
- Parameters
-
[in] | settings | The device's settings |
The send() method of AsyncManager class is paramount for this purpose. Note that std::to_string() is from C++11 onwards only. Since ROSaic can be launched before booting the Rx, we have to watch out for escape characters that are sent by the Rx to indicate that it is in upgrade mode. Those characters would then be mingled with the first command we send to it in this method and could result in an invalid command. Hence we first enter command mode via "SSSSSSSSSS".
Definition at line 389 of file communication_core.cpp.
◆ connect()
void io_comm_rx::Comm_IO::connect |
( |
| ) |
|
|
private |
◆ defineMessages()
void io_comm_rx::Comm_IO::defineMessages |
( |
| ) |
|
Defines which Rx messages to read and which ROS messages to publish.
- Parameters
-
[in] | settings | The device's settings |
initializeSerial is not self-contained: The for loop in Callbackhandlers' handle method would never open a specific handler unless the handler is added (=inserted) to the C++ map via this function. This way, the specific handler can be called, in which in turn RxMessage's read() method is called, which publishes the ROS message.
Definition at line 985 of file communication_core.cpp.
◆ initializeIO()
void io_comm_rx::Comm_IO::initializeIO |
( |
| ) |
|
◆ initializePCAPFileReading()
void io_comm_rx::Comm_IO::initializePCAPFileReading |
( |
std::string |
file_name | ) |
|
|
private |
Initializes PCAP file reading and reads PCAP file by repeatedly calling read_callback_()
- Parameters
-
[in] | file_name | The name of (or path to) the PCAP file, e.g. "/tmp/capture.pcap" |
Definition at line 1327 of file communication_core.cpp.
◆ initializeSBFFileReading()
void io_comm_rx::Comm_IO::initializeSBFFileReading |
( |
std::string |
file_name | ) |
|
|
private |
Initializes SBF file reading and reads SBF file by repeatedly calling read_callback_()
- Parameters
-
[in] | file_name | The name of (or path to) the SBF file, e.g. "xyz.sbf" |
Definition at line 1272 of file communication_core.cpp.
◆ initializeSerial()
bool io_comm_rx::Comm_IO::initializeSerial |
( |
std::string |
port, |
|
|
uint32_t |
baudrate = 115200 , |
|
|
std::string |
flowcontrol = "None" |
|
) |
| |
|
private |
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 1380 of file communication_core.cpp.
◆ initializeTCP()
bool io_comm_rx::Comm_IO::initializeTCP |
( |
std::string |
host, |
|
|
std::string |
port |
|
) |
| |
|
private |
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 1209 of file communication_core.cpp.
◆ preparePCAPFileReading()
void io_comm_rx::Comm_IO::preparePCAPFileReading |
( |
std::string |
file_name | ) |
|
|
private |
Sets up the stage for PCAP file reading.
- Parameters
-
[in] | file_name | The path to PCAP file, e.g. "/tmp/capture.sbf" |
Definition at line 285 of file communication_core.cpp.
◆ prepareSBFFileReading()
void io_comm_rx::Comm_IO::prepareSBFFileReading |
( |
std::string |
file_name | ) |
|
|
private |
Sets up the stage for SBF file reading.
- Parameters
-
[in] | file_name | The name of (or path to) the SBF file, e.g. "xyz.sbf" |
Definition at line 268 of file communication_core.cpp.
◆ reconnect()
void io_comm_rx::Comm_IO::reconnect |
( |
| ) |
|
|
private |
Attempts to (re)connect every reconnect_delay_s_ seconds.
In serial mode (not USB, since the Rx port is then called USB1 or USB2), please ensure that you are connected to the Rx's COM1, COM2 or COM3 port, !if! you employ UART hardware flow control.
Definition at line 324 of file communication_core.cpp.
◆ resetMainPort()
void io_comm_rx::Comm_IO::resetMainPort |
( |
| ) |
|
|
private |
◆ send()
void io_comm_rx::Comm_IO::send |
( |
const std::string & |
cmd | ) |
|
|
private |
◆ sendVelocity()
void io_comm_rx::Comm_IO::sendVelocity |
( |
const std::string & |
velNmea | ) |
|
Hands over NMEA velocity message over to the send() method of manager_.
- Parameters
-
cmd | The command to hand over |
Definition at line 1203 of file communication_core.cpp.
◆ setManager()
◆ CallbackHandlers
◆ RxMessage
◆ baudrate_
uint32_t io_comm_rx::Comm_IO::baudrate_ |
|
private |
◆ connected_
bool io_comm_rx::Comm_IO::connected_ = false |
|
private |
◆ connection_condition_
boost::condition_variable io_comm_rx::Comm_IO::connection_condition_ |
|
private |
Since the configureRx() method should only be called once the connection was established, we need the threads to communicate this to each other. Associated condition variable..
Definition at line 234 of file communication_core.hpp.
◆ connection_mutex_
boost::mutex io_comm_rx::Comm_IO::connection_mutex_ |
|
private |
Since the configureRx() method should only be called once the connection was established, we need the threads to communicate this to each other. Associated mutex..
Definition at line 230 of file communication_core.hpp.
◆ connectionThread_
std::unique_ptr<boost::thread> io_comm_rx::Comm_IO::connectionThread_ |
|
private |
◆ handlers_
◆ host_
std::string io_comm_rx::Comm_IO::host_ |
|
private |
◆ mainPort_
std::string io_comm_rx::Comm_IO::mainPort_ |
|
private |
◆ manager_
Processes I/O stream data This declaration is deliberately stream-independent (Serial or TCP).
Definition at line 245 of file communication_core.hpp.
◆ nmeaActivated_
bool io_comm_rx::Comm_IO::nmeaActivated_ = false |
|
private |
◆ node_
◆ port_
std::string io_comm_rx::Comm_IO::port_ |
|
private |
◆ serial_
bool io_comm_rx::Comm_IO::serial_ |
|
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 269 of file communication_core.hpp.
◆ settings_
Settings* io_comm_rx::Comm_IO::settings_ |
|
private |
◆ stopping_
std::atomic<bool> io_comm_rx::Comm_IO::stopping_ |
|
private |
◆ tcp_host_
std::string io_comm_rx::Comm_IO::tcp_host_ |
|
private |
◆ tcp_port_
std::string io_comm_rx::Comm_IO::tcp_port_ |
|
private |
The documentation for this class was generated from the following files: