Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
io_comm_rx::Comm_IO Class Reference

Handles communication with and configuration of the mosaic (and beyond) receiver(s) More...

#include <communication_core.hpp>

Public Member Functions

 Comm_IO (ROSaicNodeBase *node, Settings *settings)
 Constructor of the class Comm_IO. More...
 
void configureRx ()
 Configures Rx: Which SBF/NMEA messages it should output and later correction settings. More...
 
void defineMessages ()
 Defines which Rx messages to read and which ROS messages to publish. More...
 
void initializeIO ()
 Initializes the I/O handling. More...
 
void sendVelocity (const std::string &velNmea)
 Hands over NMEA velocity message over to the send() method of manager_. More...
 
 ~Comm_IO ()
 Default destructor of the class Comm_IO. More...
 

Private Member Functions

void connect ()
 Calls the reconnect() method. More...
 
void initializePCAPFileReading (std::string file_name)
 Initializes PCAP file reading and reads PCAP file by repeatedly calling read_callback_() More...
 
void initializeSBFFileReading (std::string file_name)
 Initializes SBF file reading and reads SBF file by repeatedly calling read_callback_() 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 preparePCAPFileReading (std::string file_name)
 Sets up the stage for PCAP file reading. More...
 
void prepareSBFFileReading (std::string file_name)
 Sets up the stage for SBF file reading. More...
 
void reconnect ()
 Attempts to (re)connect every reconnect_delay_s_ seconds. More...
 
void resetMainPort ()
 Reset main port so it can receive commands. More...
 
void send (const std::string &)
 Hands over to the send() method of manager_. More...
 
void setManager (const boost::shared_ptr< Manager > &manager)
 Set the I/O manager. More...
 

Private Attributes

uint32_t baudrate_
 Baudrate at the moment, unless InitializeSerial or ResetSerial fail. More...
 
bool connected_ = false
 Whether connecting to Rx was successful. More...
 
boost::condition_variable connection_condition_
 
boost::mutex connection_mutex_
 
std::unique_ptr< boost::thread > connectionThread_
 Connection or reading thread. More...
 
CallbackHandlers handlers_
 Callback handlers for the inwards streaming messages. More...
 
std::string host_
 Host currently connected to. More...
 
std::string mainPort_
 Communication ports. More...
 
boost::shared_ptr< Managermanager_
 
bool nmeaActivated_ = false
 
ROSaicNodeBasenode_
 Pointer to Node. More...
 
std::string port_
 Port over which TCP/IP connection is currently established. More...
 
bool serial_
 Whether yet-to-be-established connection to Rx will be serial or TCP. More...
 
std::string serial_port_
 Saves the port description. More...
 
Settingssettings_
 Settings. More...
 
std::atomic< bool > stopping_
 Indicator for threads to exit. More...
 
std::string tcp_host_
 Host name of TCP server. More...
 
std::string tcp_port_
 TCP port number. More...
 

Static Private Attributes

static const unsigned int SET_BAUDRATE_SLEEP_ = 500000
 

Friends

class CallbackHandlers
 
class RxMessage
 

Detailed Description

Handles communication with and configuration of the mosaic (and beyond) receiver(s)

Definition at line 106 of file communication_core.hpp.

Constructor & Destructor Documentation

◆ Comm_IO()

io_comm_rx::Comm_IO::Comm_IO ( ROSaicNodeBase node,
Settings settings 
)

Constructor of the class Comm_IO.

Parameters
[in]nodePointer to node

Definition at line 122 of file communication_core.cpp.

◆ ~Comm_IO()

io_comm_rx::Comm_IO::~Comm_IO ( )

Default destructor of the class Comm_IO.

Definition at line 131 of file communication_core.cpp.

Member Function Documentation

◆ configureRx()

void io_comm_rx::Comm_IO::configureRx ( )

Configures Rx: Which SBF/NMEA messages it should output and later correction settings.

Parameters
[in]settingsThe 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

Calls the reconnect() method.

Definition at line 302 of file communication_core.cpp.

◆ defineMessages()

void io_comm_rx::Comm_IO::defineMessages ( )

Defines which Rx messages to read and which ROS messages to publish.

Parameters
[in]settingsThe 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 ( )

Initializes the I/O handling.

Definition at line 206 of file communication_core.cpp.

◆ 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_nameThe 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_nameThe 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]portThe device's port address
[in]baudrateThe chosen baud rate of the port
[in]flowcontrolDefault 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]hostThe TCP host
[in]portThe 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_nameThe 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_nameThe 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

Reset main port so it can receive commands.

Definition at line 191 of file communication_core.cpp.

◆ send()

void io_comm_rx::Comm_IO::send ( const std::string &  cmd)
private

Hands over to the send() method of manager_.

Parameters
cmdThe command to hand over

Definition at line 1192 of file communication_core.cpp.

◆ 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
cmdThe command to hand over

Definition at line 1203 of file communication_core.cpp.

◆ setManager()

void io_comm_rx::Comm_IO::setManager ( const boost::shared_ptr< Manager > &  manager)
private

Set the I/O manager.

Parameters
[in]managerAn I/O handler

Definition at line 1550 of file communication_core.cpp.

Friends And Related Function Documentation

◆ CallbackHandlers

friend class CallbackHandlers
friend

Definition at line 256 of file communication_core.hpp.

◆ RxMessage

friend class RxMessage
friend

Definition at line 257 of file communication_core.hpp.

Member Data Documentation

◆ baudrate_

uint32_t io_comm_rx::Comm_IO::baudrate_
private

Baudrate at the moment, unless InitializeSerial or ResetSerial fail.

Definition at line 247 of file communication_core.hpp.

◆ connected_

bool io_comm_rx::Comm_IO::connected_ = false
private

Whether connecting to Rx was successful.

Definition at line 226 of file communication_core.hpp.

◆ 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

Connection or reading thread.

Definition at line 252 of file communication_core.hpp.

◆ handlers_

CallbackHandlers io_comm_rx::Comm_IO::handlers_
private

Callback handlers for the inwards streaming messages.

Definition at line 222 of file communication_core.hpp.

◆ host_

std::string io_comm_rx::Comm_IO::host_
private

Host currently connected to.

Definition at line 263 of file communication_core.hpp.

◆ mainPort_

std::string io_comm_rx::Comm_IO::mainPort_
private

Communication ports.

Definition at line 260 of file communication_core.hpp.

◆ manager_

boost::shared_ptr<Manager> io_comm_rx::Comm_IO::manager_
private

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

Definition at line 249 of file communication_core.hpp.

◆ node_

ROSaicNodeBase* io_comm_rx::Comm_IO::node_
private

Pointer to Node.

Definition at line 220 of file communication_core.hpp.

◆ port_

std::string io_comm_rx::Comm_IO::port_
private

Port over which TCP/IP connection is currently established.

Definition at line 265 of file communication_core.hpp.

◆ serial_

bool io_comm_rx::Comm_IO::serial_
private

Whether yet-to-be-established connection to Rx will be serial or TCP.

Definition at line 240 of file communication_core.hpp.

◆ serial_port_

std::string io_comm_rx::Comm_IO::serial_port_
private

Saves the port description.

Definition at line 242 of file communication_core.hpp.

◆ 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

Settings.

Definition at line 224 of file communication_core.hpp.

◆ stopping_

std::atomic<bool> io_comm_rx::Comm_IO::stopping_
private

Indicator for threads to exit.

Definition at line 254 of file communication_core.hpp.

◆ tcp_host_

std::string io_comm_rx::Comm_IO::tcp_host_
private

Host name of TCP server.

Definition at line 236 of file communication_core.hpp.

◆ tcp_port_

std::string io_comm_rx::Comm_IO::tcp_port_
private

TCP port number.

Definition at line 238 of file communication_core.hpp.


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


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56