Go to the documentation of this file.
59 #ifndef COMMUNICATION_CORE_HPP // This block is called a conditional group. The
63 #define COMMUNICATION_CORE_HPP // Include guards help to avoid the double inclusion
67 #include <boost/asio.hpp>
68 #include <boost/asio/serial_port.hpp>
69 #include <boost/bind.hpp>
70 #include <boost/date_time/posix_time/posix_time.hpp>
71 #include <boost/exception/diagnostic_information.hpp>
72 #include <boost/function.hpp>
97 1200, 2400, 4800, 9600, 19200, 38400, 57600,
98 115200, 230400, 460800, 500000, 576000, 921600, 1000000,
99 1152000, 1500000, 2000000, 2500000, 3000000, 3500000, 4000000};
182 std::string flowcontrol =
"None");
217 void send(
const std::string&);
273 #endif // for COMMUNICATION_CORE_HPP
boost::mutex connection_mutex_
void resetMainPort()
Reset main port so it can receive commands.
const static uint32_t BAUDRATES[]
Possible baudrates for the Rx.
std::string tcp_port_
TCP port number.
std::string host_
Host currently connected to.
void send(const std::string &)
Hands over to the send() method of manager_.
Implements asynchronous operations for an I/O manager.
Comm_IO(ROSaicNodeBase *node, Settings *settings)
Constructor of the class Comm_IO.
void prepareSBFFileReading(std::string file_name)
Sets up the stage for SBF file reading.
void initializeIO()
Initializes the I/O handling.
boost::condition_variable connection_condition_
Settings * settings_
Settings.
Handles callbacks when reading NMEA/SBF messages.
CallbackHandlers handlers_
Callback handlers for the inwards streaming messages.
std::atomic< bool > stopping_
Indicator for threads to exit.
void sendVelocity(const std::string &velNmea)
Hands over NMEA velocity message over to the send() method of manager_.
This class is the base class for abstraction.
std::unique_ptr< boost::thread > connectionThread_
Connection or reading thread.
uint32_t baudrate_
Baudrate at the moment, unless InitializeSerial or ResetSerial fail.
Handles communication with and configuration of the mosaic (and beyond) receiver(s)
const static unsigned int SET_BAUDRATE_SLEEP_
ROSaicNodeBase * node_
Pointer to Node.
void connect()
Calls the reconnect() method.
void initializeSBFFileReading(std::string file_name)
Initializes SBF file reading and reads SBF file by repeatedly calling read_callback_()
Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class.
std::string tcp_host_
Host name of TCP server.
void setManager(const boost::shared_ptr< Manager > &manager)
Set the I/O manager.
void preparePCAPFileReading(std::string file_name)
Sets up the stage for PCAP file reading.
std::string serial_port_
Saves the port description.
void reconnect()
Attempts to (re)connect every reconnect_delay_s_ seconds.
std::string mainPort_
Communication ports.
bool initializeSerial(std::string port, uint32_t baudrate=115200, std::string flowcontrol="None")
Initializes the serial port.
void initializePCAPFileReading(std::string file_name)
Initializes PCAP file reading and reads PCAP file by repeatedly calling read_callback_()
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
bool serial_
Whether yet-to-be-established connection to Rx will be serial or TCP.
bool initializeTCP(std::string host, std::string port)
Initializes the TCP I/O.
std::string port_
Port over which TCP/IP connection is currently established.
Can search buffer for messages, read/parse them, and so on.
boost::shared_ptr< Manager > manager_
~Comm_IO()
Default destructor of the class Comm_IO.
bool connected_
Whether connecting to Rx was successful.
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.