communication_core.hpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // © Copyright 2020, Septentrio NV/SA.
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // 1. Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // 2. Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // 3. Neither the name of the copyright holder nor the names of its
14 // contributors may be used to endorse or promote products derived
15 // from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 // *****************************************************************************
30 
31 // *****************************************************************************
32 //
33 // Boost Software License - Version 1.0 - August 17th, 2003
34 //
35 // Permission is hereby granted, free of charge, to any person or organization
36 // obtaining a copy of the software and accompanying documentation covered by
37 // this license (the "Software") to use, reproduce, display, distribute,
38 // execute, and transmit the Software, and to prepare derivative works of the
39 // Software, and to permit third-parties to whom the Software is furnished to
40 // do so, all subject to the following:
41 
42 // The copyright notices in the Software and this entire statement, including
43 // the above license grant, this restriction and the following disclaimer,
44 // must be included in all copies of the Software, in whole or in part, and
45 // all derivative works of the Software, unless such copies or derivative
46 // works are solely in the form of machine-executable object code generated by
47 // a source language processor.
48 //
49 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
50 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
51 // FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
52 // SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
53 // FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
54 // ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
55 // DEALINGS IN THE SOFTWARE.
56 //
57 // *****************************************************************************
58 
59 #ifndef COMMUNICATION_CORE_HPP // This block is called a conditional group. The
60  // controlled text will get included in the
61  // preprocessor output iff the macroname is not
62  // defined.
63 #define COMMUNICATION_CORE_HPP // Include guards help to avoid the double inclusion
64  // of header files, by defining a token = macro.
65 
66 // Boost includes
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> // dealing with bad file descriptor error
72 #include <boost/function.hpp>
73 // C++ library includes
74 #include <fstream>
75 #include <memory>
76 #include <sstream>
77 #include <unistd.h> // for usleep()
78 // ROSaic includes
81 
93 namespace io_comm_rx {
94 
96  const static uint32_t BAUDRATES[] = {
97  1200, 2400, 4800, 9600, 19200, 38400, 57600,
98  115200, 230400, 460800, 500000, 576000, 921600, 1000000,
99  1152000, 1500000, 2000000, 2500000, 3000000, 3500000, 4000000};
100 
106  class Comm_IO
107  {
108  public:
113  Comm_IO(ROSaicNodeBase* node, Settings* settings);
117  ~Comm_IO();
118 
122  void initializeIO();
123 
129  void configureRx();
130 
135  void defineMessages();
136 
142  void sendVelocity(const std::string& velNmea);
143 
144  private:
148  void resetMainPort();
149 
154  void prepareSBFFileReading(std::string file_name);
155 
160  void preparePCAPFileReading(std::string file_name);
161 
165  void reconnect();
166 
170  void connect();
171 
181  bool initializeSerial(std::string port, uint32_t baudrate = 115200,
182  std::string flowcontrol = "None");
183 
190  bool initializeTCP(std::string host, std::string port);
191 
197  void initializeSBFFileReading(std::string file_name);
198 
205  void initializePCAPFileReading(std::string file_name);
206 
211  void setManager(const boost::shared_ptr<Manager>& manager);
212 
217  void send(const std::string&);
218 
226  bool connected_ = false;
230  boost::mutex connection_mutex_;
234  boost::condition_variable connection_condition_;
236  std::string tcp_host_;
238  std::string tcp_port_;
240  bool serial_;
242  std::string serial_port_;
247  uint32_t baudrate_;
248 
249  bool nmeaActivated_ = false;
250 
252  std::unique_ptr<boost::thread> connectionThread_;
254  std::atomic<bool> stopping_;
255 
256  friend class CallbackHandlers;
257  friend class RxMessage;
258 
260  std::string mainPort_;
261 
263  std::string host_;
265  std::string port_;
269  const static unsigned int SET_BAUDRATE_SLEEP_ = 500000;
270  };
271 } // namespace io_comm_rx
272 
273 #endif // for COMMUNICATION_CORE_HPP
bool connected_
Whether connecting to Rx was successful.
boost::shared_ptr< Manager > manager_
uint32_t baudrate_
Baudrate at the moment, unless InitializeSerial or ResetSerial fail.
void send(const std::string &)
Hands over to the send() method of manager_.
Settings * settings_
Settings.
Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class...
void prepareSBFFileReading(std::string file_name)
Sets up the stage for SBF file reading.
Comm_IO(ROSaicNodeBase *node, Settings *settings)
Constructor of the class Comm_IO.
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.
bool serial_
Whether yet-to-be-established connection to Rx will be serial or TCP.
static const unsigned int SET_BAUDRATE_SLEEP_
bool initializeSerial(std::string port, uint32_t baudrate=115200, std::string flowcontrol="None")
Initializes the serial port.
void initializeIO()
Initializes the I/O handling.
void initializeSBFFileReading(std::string file_name)
Initializes SBF file reading and reads SBF file by repeatedly calling read_callback_() ...
std::unique_ptr< boost::thread > connectionThread_
Connection or reading thread.
void reconnect()
Attempts to (re)connect every reconnect_delay_s_ seconds.
Implements asynchronous operations for an I/O manager.
std::string serial_port_
Saves the port description.
ROSaicNodeBase * node_
Pointer to Node.
std::string port_
Port over which TCP/IP connection is currently established.
bool initializeTCP(std::string host, std::string port)
Initializes the TCP I/O.
void resetMainPort()
Reset main port so it can receive commands.
Settings struct.
Definition: settings.h:103
static const uint32_t BAUDRATES[]
Possible baudrates for the Rx.
~Comm_IO()
Default destructor of the class Comm_IO.
void preparePCAPFileReading(std::string file_name)
Sets up the stage for PCAP file reading.
std::string mainPort_
Communication ports.
void sendVelocity(const std::string &velNmea)
Hands over NMEA velocity message over to the send() method of manager_.
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
std::string tcp_port_
TCP port number.
boost::condition_variable connection_condition_
std::atomic< bool > stopping_
Indicator for threads to exit.
void setManager(const boost::shared_ptr< Manager > &manager)
Set the I/O manager.
CallbackHandlers handlers_
Callback handlers for the inwards streaming messages.
Handles callbacks when reading NMEA/SBF messages.
This class is the base class for abstraction.
Definition: typedefs.hpp:174
Can search buffer for messages, read/parse them, and so on.
Definition: rx_message.hpp:201
void initializePCAPFileReading(std::string file_name)
Initializes PCAP file reading and reads PCAP file by repeatedly calling read_callback_() ...
void connect()
Calls the reconnect() method.
std::string tcp_host_
Host name of TCP server.
Handles communication with and configuration of the mosaic (and beyond) receiver(s) ...
std::string host_
Host currently connected to.


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