message_handler.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 #pragma once
60 
61 // C++ libraries
62 #include <cassert> // for assert
63 #include <cstddef>
64 #include <map>
65 #include <sstream>
66 // Boost includes
67 #include <boost/call_traits.hpp>
68 #include <boost/format.hpp>
69 #include <boost/math/constants/constants.hpp>
70 #include <boost/tokenizer.hpp>
71 // ROSaic includes
80 
86 enum TypeOfPVT_Enum
89 {
100 };
101 
102 enum SbfId
103 {
105  PVT_GEODETIC = 4007,
110  ATT_EULER = 5938,
113  MEAS_EPOCH = 4027,
114  DOP = 4001,
118  QUALITY_IND = 4082,
120  INS_NAV_CART = 4225,
121  INS_NAV_GEOD = 4226,
124  IMU_SETUP = 4224,
129  RF_STATUS = 4092
130 };
131 
132 namespace io {
133 
139  {
140  public:
146  node_(node), settings_(node->settings()), unix_time_(0)
147  {
148  }
149 
151  {
152  // set leap seconds to paramter if reading from file
155  }
156 
161  void parseSbf(const std::shared_ptr<Telegram>& telegram);
162 
167  void parseNmea(const std::shared_ptr<Telegram>& telegram);
168 
169  private:
176  template <typename T>
177  void assembleHeader(const std::string& frameId,
178  const std::shared_ptr<Telegram>& telegram, T& msg) const;
184  template <typename M>
185  void publish(const std::string& topic, const M& msg);
186 
192  void publishTf(const LocalizationMsg& msg);
193 
198 
203 
207  std::unordered_map<std::string, uint8_t> nmeaMap_{
208  {"$GPGGA", 0}, {"$INGGA", 0}, {"$GPRMC", 1}, {"$INRMC", 1},
209  {"$GPGSA", 2}, {"$INGSA", 2}, {"$GAGSV", 3}, {"$INGSV", 3}};
210 
216 
222 
228 
234 
240 
246 
252 
258 
264 
269 
275 
281 
287 
293 
298 
302  bool osnma_info_available_ = false;
303 
308 
312 
314  mutable uint64_t last_pvt_latency_ = 0;
315 
317  int32_t current_leap_seconds_ = -128;
318 
322  void assembleNavSatFix();
323 
327  void assembleGpsFix();
328 
334 
340  void assembleDiagnosticArray(const std::shared_ptr<Telegram>& telegram);
341 
347 
353 
358  void assembleImu();
359 
365 
371 
379  void assembleLocalizationMsgTwist(double roll, double pitch, double yaw,
380  LocalizationMsg& msg) const;
381 
387  void assembleTwist(bool fromIns = false);
388 
394  void assembleTimeReference(const std::shared_ptr<Telegram>& telegram);
395 
400  void wait(Timestamp time_obj);
401 
405  std::shared_ptr<std::string> fixedUtmZone_;
406 
415  Timestamp timestampSBF(const std::vector<uint8_t>& message) const;
416 
428  Timestamp timestampSBF(uint32_t tow, uint16_t wnc) const;
429  };
430 } // namespace io
evMovingBaseRTKFixed
@ evMovingBaseRTKFixed
Definition: message_handler.hpp:97
Timestamp
uint64_t Timestamp
Definition: typedefs.hpp:92
io::MessageHandler::fixedUtmZone_
std::shared_ptr< std::string > fixedUtmZone_
Fixed UTM zone.
Definition: message_handler.hpp:405
QualityInd
Struct for the SBF block "QualityInd".
Definition: sbf_blocks.hpp:194
evDGPS
@ evDGPS
Definition: message_handler.hpp:92
gprmc.hpp
Derived class for parsing RMC messages.
io::MessageHandler::timestampSBF
Timestamp timestampSBF(const std::vector< uint8_t > &message) const
Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmit...
Definition: message_handler.cpp:2105
INS_NAV_CART
@ INS_NAV_CART
Definition: message_handler.hpp:120
ATT_COV_EULER
@ ATT_COV_EULER
Definition: message_handler.hpp:111
RECEIVER_TIME
@ RECEIVER_TIME
Definition: message_handler.hpp:127
INS_NAV_GEOD
@ INS_NAV_GEOD
Definition: message_handler.hpp:121
LocalizationMsg
nav_msgs::Odometry LocalizationMsg
Definition: typedefs.hpp:109
io::MessageHandler::assembleHeader
void assembleHeader(const std::string &frameId, const std::shared_ptr< Telegram > &telegram, T &msg) const
Header assembling.
Definition: message_handler.cpp:2069
MEAS_EPOCH
@ MEAS_EPOCH
Definition: message_handler.hpp:113
crc.hpp
Declares the functions to compute and validate the CRC of a buffer.
gpgga.hpp
Derived class for parsing GGA messages.
POS_COV_GEODETIC
@ POS_COV_GEODETIC
Definition: message_handler.hpp:109
io::MessageHandler::publishTf
void publishTf(const LocalizationMsg &msg)
Publishing function.
Definition: message_handler.cpp:2177
io::MessageHandler::last_rf_status_
RfStatusMsg last_rf_status_
Stores incoming RFStatus block.
Definition: message_handler.hpp:307
POS_COV_CARTESIAN
@ POS_COV_CARTESIAN
Definition: message_handler.hpp:108
io::MessageHandler::last_qualityind_
QualityInd last_qualityind_
Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored.
Definition: message_handler.hpp:286
QUALITY_IND
@ QUALITY_IND
Definition: message_handler.hpp:118
io::MessageHandler::last_receiversetup_
ReceiverSetup last_receiversetup_
Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored.
Definition: message_handler.hpp:292
io::MessageHandler::last_atteuler_
AttEulerMsg last_atteuler_
Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored.
Definition: message_handler.hpp:227
ATT_EULER
@ ATT_EULER
Definition: message_handler.hpp:110
BASE_VECTOR_CART
@ BASE_VECTOR_CART
Definition: message_handler.hpp:106
IMU_SETUP
@ IMU_SETUP
Definition: message_handler.hpp:124
io::MessageHandler::assemblePoseWithCovarianceStamped
void assemblePoseWithCovarianceStamped()
"Callback" function when constructing PoseWithCovarianceStamped messages
Definition: message_handler.cpp:57
io::MessageHandler::assembleTimeReference
void assembleTimeReference(const std::shared_ptr< Telegram > &telegram)
function when constructing TimeReferenceMsg messages
Definition: message_handler.cpp:2058
EXT_EVENT_INS_NAV_CART
@ EXT_EVENT_INS_NAV_CART
Definition: message_handler.hpp:123
VelCovGeodeticMsg
septentrio_gnss_driver::VelCovGeodetic VelCovGeodeticMsg
Definition: typedefs.hpp:132
io::MessageHandler::assembleGpsFix
void assembleGpsFix()
"Callback" function when constructing GPSFix messages
Definition: message_handler.cpp:1590
telegram.hpp
io::MessageHandler::last_measepoch_
MeasEpochMsg last_measepoch_
Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored.
Definition: message_handler.hpp:263
evStandAlone
@ evStandAlone
Definition: message_handler.hpp:91
io::MessageHandler::current_leap_seconds_
int32_t current_leap_seconds_
Current leap seconds as received, do not use value is -128.
Definition: message_handler.hpp:317
io::MessageHandler::assembleAimAndDiagnosticArray
void assembleAimAndDiagnosticArray()
"Callback" function when constructing RFStatus DiagnosticArrayMsg messages
Definition: message_handler.cpp:446
GAL_AUTH_STATUS
@ GAL_AUTH_STATUS
Definition: message_handler.hpp:128
INSNavCartMsg
septentrio_gnss_driver::INSNavCart INSNavCartMsg
Definition: typedefs.hpp:141
ROSaicNodeBase
This class is the base class for abstraction.
Definition: typedefs.hpp:184
io::MessageHandler::assembleDiagnosticArray
void assembleDiagnosticArray(const std::shared_ptr< Telegram > &telegram)
"Callback" function when constructing DiagnosticArrayMsg messages
Definition: message_handler.cpp:216
VEL_COV_GEODETIC
@ VEL_COV_GEODETIC
Definition: message_handler.hpp:116
io::MessageHandler::assembleLocalizationMsgTwist
void assembleLocalizationMsgTwist(double roll, double pitch, double yaw, LocalizationMsg &msg) const
function to fill twist part of LocalizationMsg
Definition: message_handler.cpp:1255
EXT_SENSOR_MEAS
@ EXT_SENSOR_MEAS
Definition: message_handler.hpp:126
DOP
Struct for the SBF block "DOP".
PVTGeodeticMsg
septentrio_gnss_driver::PVTGeodetic PVTGeodeticMsg
Definition: typedefs.hpp:125
PosCovGeodeticMsg
septentrio_gnss_driver::PosCovGeodetic PosCovGeodeticMsg
Definition: typedefs.hpp:127
GalAuthStatusMsg
septentrio_gnss_driver::GALAuthStatus GalAuthStatusMsg
Definition: typedefs.hpp:116
io::MessageHandler::settings_
const Settings * settings_
Pointer to settings struct.
Definition: message_handler.hpp:202
io::MessageHandler::nmeaMap_
std::unordered_map< std::string, uint8_t > nmeaMap_
Map of NMEA messgae IDs and uint8_t.
Definition: message_handler.hpp:207
io::MessageHandler::last_pvtgeodetic_
PVTGeodeticMsg last_pvtgeodetic_
Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored.
Definition: message_handler.hpp:215
PVT_GEODETIC
@ PVT_GEODETIC
Definition: message_handler.hpp:105
evRTKFixed
@ evRTKFixed
Definition: message_handler.hpp:94
io::MessageHandler::last_gal_auth_status_
GalAuthStatusMsg last_gal_auth_status_
Stores incoming GALAuthStatus block.
Definition: message_handler.hpp:297
evFixed
@ evFixed
Definition: message_handler.hpp:93
io::MessageHandler::parseNmea
void parseNmea(const std::shared_ptr< Telegram > &telegram)
Parse NMEA block.
Definition: message_handler.cpp:2754
Dop
Definition: sbf_blocks.hpp:145
AttCovEulerMsg
septentrio_gnss_driver::AttCovEuler AttCovEulerMsg
Definition: typedefs.hpp:122
io
Definition: async_manager.hpp:83
io::MessageHandler
Can search buffer for messages, read/parse them, and so on.
Definition: message_handler.hpp:138
io::MessageHandler::assembleNavSatFix
void assembleNavSatFix()
"Callback" function when constructing NavSatFix messages
Definition: message_handler.cpp:1378
TypeOfPVT_Enum
TypeOfPVT_Enum
Definition: message_handler.hpp:88
io::MessageHandler::assembleImu
void assembleImu()
"Callback" function when constructing ImuMsg messages
Definition: message_handler.cpp:548
INSNavGeodMsg
septentrio_gnss_driver::INSNavGeod INSNavGeodMsg
Definition: typedefs.hpp:142
io::MessageHandler::setLeapSeconds
void setLeapSeconds()
Definition: message_handler.hpp:150
io::MessageHandler::assembleLocalizationEcef
void assembleLocalizationEcef()
"Callback" function when constructing LocalizationMsg messages in ECEF
Definition: message_handler.cpp:1091
io::MessageHandler::last_attcoveuler_
AttCovEulerMsg last_attcoveuler_
Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored.
Definition: message_handler.hpp:233
typedefs.hpp
RECEIVER_SETUP
@ RECEIVER_SETUP
Definition: message_handler.hpp:119
Settings
Settings struct.
Definition: settings.hpp:123
io::MessageHandler::last_pvt_latency_
uint64_t last_pvt_latency_
Last reported PVT processing latency.
Definition: message_handler.hpp:314
io::MessageHandler::osnma_info_available_
bool osnma_info_available_
Wether OSNMA info has been received.
Definition: message_handler.hpp:302
evSBAS
@ evSBAS
Definition: message_handler.hpp:96
ExtSensorMeasMsg
septentrio_gnss_driver::ExtSensorMeas ExtSensorMeasMsg
Definition: typedefs.hpp:145
ChannelStatus
Struct for the SBF block "ChannelStatus".
Definition: sbf_blocks.hpp:130
io::MessageHandler::publish
void publish(const std::string &topic, const M &msg)
Publishing function.
Definition: message_handler.cpp:2148
Settings::read_from_sbf_log
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
Definition: settings.hpp:333
PVT_CARTESIAN
@ PVT_CARTESIAN
Definition: message_handler.hpp:104
gpgsa.hpp
Derived class for parsing GSA messages.
io::MessageHandler::parseSbf
void parseSbf(const std::shared_ptr< Telegram > &telegram)
Parse SBF block.
Definition: message_handler.cpp:2203
ReceiverSetup
Struct for the SBF block "ReceiverSetup".
Definition: sbf_blocks.hpp:162
io::MessageHandler::last_dop_
Dop last_dop_
Since GPSFix needs DOP, incoming DOP blocks need to be stored.
Definition: message_handler.hpp:268
evNoPVT
@ evNoPVT
Definition: message_handler.hpp:90
string_utilities.hpp
Declares lower-level string utility functions used when parsing messages.
Settings::leap_seconds
int32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
Definition: settings.hpp:331
RfStatusMsg
septentrio_gnss_driver::RFStatus RfStatusMsg
Definition: typedefs.hpp:117
io::MessageHandler::last_channelstatus_
ChannelStatus last_channelstatus_
Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored.
Definition: message_handler.hpp:257
VEL_COV_CARTESIAN
@ VEL_COV_CARTESIAN
Definition: message_handler.hpp:115
RF_STATUS
@ RF_STATUS
Definition: message_handler.hpp:129
BASE_VECTOR_GEOD
@ BASE_VECTOR_GEOD
Definition: message_handler.hpp:107
VEL_SENSOR_SETUP
@ VEL_SENSOR_SETUP
Definition: message_handler.hpp:125
evPPP
@ evPPP
Definition: message_handler.hpp:99
io::MessageHandler::last_extsensmeas_
ExtSensorMeasMsg last_extsensmeas_
Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored.
Definition: message_handler.hpp:251
EXT_EVENT_INS_NAV_GEOD
@ EXT_EVENT_INS_NAV_GEOD
Definition: message_handler.hpp:122
MeasEpochMsg
septentrio_gnss_driver::MeasEpoch MeasEpochMsg
Definition: typedefs.hpp:119
io::MessageHandler::assembleLocalizationUtm
void assembleLocalizationUtm()
"Callback" function when constructing LocalizationMsg messages in UTM
Definition: message_handler.cpp:887
io::MessageHandler::MessageHandler
MessageHandler(ROSaicNodeBase *node)
Constructor of the MessageHandler class.
Definition: message_handler.hpp:145
SbfId
SbfId
Definition: message_handler.hpp:102
evMovingBaseRTKFloat
@ evMovingBaseRTKFloat
Definition: message_handler.hpp:98
io::MessageHandler::last_receiverstatus_
ReceiverStatus last_receiverstatus_
Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored.
Definition: message_handler.hpp:280
evRTKFloat
@ evRTKFloat
Definition: message_handler.hpp:95
RECEIVER_STATUS
@ RECEIVER_STATUS
Definition: message_handler.hpp:117
io::MessageHandler::last_velcovgeodetic_
VelCovGeodeticMsg last_velcovgeodetic_
Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored.
Definition: message_handler.hpp:274
io::MessageHandler::node_
ROSaicNodeBase * node_
Pointer to the node.
Definition: message_handler.hpp:197
ReceiverStatus
Struct for the SBF block "ReceiverStatus".
Definition: sbf_blocks.hpp:218
gpgsv.hpp
Derived class for parsing GSV messages.
io::MessageHandler::last_insnavcart_
INSNavCartMsg last_insnavcart_
Since LoclaizationEcef needs INSNavCart, incoming INSNavCart blocks need to be stored.
Definition: message_handler.hpp:245
io::MessageHandler::last_poscovgeodetic_
PosCovGeodeticMsg last_poscovgeodetic_
Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored.
Definition: message_handler.hpp:221
io::MessageHandler::wait
void wait(Timestamp time_obj)
Waits according to time when reading from file.
Definition: message_handler.cpp:2738
io::MessageHandler::assembleOsnmaDiagnosticArray
void assembleOsnmaDiagnosticArray()
"Callback" function when constructing OSNMA DiagnosticArrayMsg messages
Definition: message_handler.cpp:353
CHANNEL_STATUS
@ CHANNEL_STATUS
Definition: message_handler.hpp:112
io::MessageHandler::unix_time_
Timestamp unix_time_
Definition: message_handler.hpp:311
Settings::read_from_pcap
bool read_from_pcap
Whether or not we are reading from a PCAP file.
Definition: settings.hpp:335
io::MessageHandler::last_insnavgeod_
INSNavGeodMsg last_insnavgeod_
Since NavSatFix, GPSFix, Imu and Pose need INSNavGeod, incoming INSNavGeod blocks need to be stored.
Definition: message_handler.hpp:239
io::MessageHandler::assembleTwist
void assembleTwist(bool fromIns=false)
"Callback" function when constructing TwistWithCovarianceStampedMsg messages
Definition: message_handler.cpp:659
AttEulerMsg
septentrio_gnss_driver::AttEuler AttEulerMsg
Definition: typedefs.hpp:123


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Wed Nov 22 2023 04:04:27