Go to the documentation of this file.
67 #include <boost/call_traits.hpp>
68 #include <boost/format.hpp>
69 #include <boost/math/constants/constants.hpp>
70 #include <boost/tokenizer.hpp>
161 void parseSbf(
const std::shared_ptr<Telegram>& telegram);
167 void parseNmea(
const std::shared_ptr<Telegram>& telegram);
176 template <
typename T>
178 const std::shared_ptr<Telegram>& telegram, T& msg)
const;
184 template <
typename M>
185 void publish(
const std::string& topic,
const M& msg);
208 {
"$GPGGA", 0}, {
"$INGGA", 0}, {
"$GPRMC", 1}, {
"$INRMC", 1},
209 {
"$GPGSA", 2}, {
"$INGSA", 2}, {
"$GAGSV", 3}, {
"$INGSV", 3}};
std::shared_ptr< std::string > fixedUtmZone_
Fixed UTM zone.
Struct for the SBF block "QualityInd".
Derived class for parsing RMC messages.
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...
nav_msgs::Odometry LocalizationMsg
void assembleHeader(const std::string &frameId, const std::shared_ptr< Telegram > &telegram, T &msg) const
Header assembling.
Declares the functions to compute and validate the CRC of a buffer.
Derived class for parsing GGA messages.
void publishTf(const LocalizationMsg &msg)
Publishing function.
RfStatusMsg last_rf_status_
Stores incoming RFStatus block.
QualityInd last_qualityind_
Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored.
ReceiverSetup last_receiversetup_
Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored.
AttEulerMsg last_atteuler_
Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored.
void assemblePoseWithCovarianceStamped()
"Callback" function when constructing PoseWithCovarianceStamped messages
void assembleTimeReference(const std::shared_ptr< Telegram > &telegram)
function when constructing TimeReferenceMsg messages
septentrio_gnss_driver::VelCovGeodetic VelCovGeodeticMsg
void assembleGpsFix()
"Callback" function when constructing GPSFix messages
MeasEpochMsg last_measepoch_
Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored.
int32_t current_leap_seconds_
Current leap seconds as received, do not use value is -128.
void assembleAimAndDiagnosticArray()
"Callback" function when constructing RFStatus DiagnosticArrayMsg messages
septentrio_gnss_driver::INSNavCart INSNavCartMsg
This class is the base class for abstraction.
void assembleDiagnosticArray(const std::shared_ptr< Telegram > &telegram)
"Callback" function when constructing DiagnosticArrayMsg messages
void assembleLocalizationMsgTwist(double roll, double pitch, double yaw, LocalizationMsg &msg) const
function to fill twist part of LocalizationMsg
Struct for the SBF block "DOP".
septentrio_gnss_driver::PVTGeodetic PVTGeodeticMsg
septentrio_gnss_driver::PosCovGeodetic PosCovGeodeticMsg
septentrio_gnss_driver::GALAuthStatus GalAuthStatusMsg
const Settings * settings_
Pointer to settings struct.
std::unordered_map< std::string, uint8_t > nmeaMap_
Map of NMEA messgae IDs and uint8_t.
PVTGeodeticMsg last_pvtgeodetic_
Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored.
GalAuthStatusMsg last_gal_auth_status_
Stores incoming GALAuthStatus block.
void parseNmea(const std::shared_ptr< Telegram > &telegram)
Parse NMEA block.
septentrio_gnss_driver::AttCovEuler AttCovEulerMsg
Can search buffer for messages, read/parse them, and so on.
void assembleNavSatFix()
"Callback" function when constructing NavSatFix messages
void assembleImu()
"Callback" function when constructing ImuMsg messages
septentrio_gnss_driver::INSNavGeod INSNavGeodMsg
void assembleLocalizationEcef()
"Callback" function when constructing LocalizationMsg messages in ECEF
AttCovEulerMsg last_attcoveuler_
Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored.
uint64_t last_pvt_latency_
Last reported PVT processing latency.
bool osnma_info_available_
Wether OSNMA info has been received.
septentrio_gnss_driver::ExtSensorMeas ExtSensorMeasMsg
Struct for the SBF block "ChannelStatus".
void publish(const std::string &topic, const M &msg)
Publishing function.
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
Derived class for parsing GSA messages.
void parseSbf(const std::shared_ptr< Telegram > &telegram)
Parse SBF block.
Struct for the SBF block "ReceiverSetup".
Dop last_dop_
Since GPSFix needs DOP, incoming DOP blocks need to be stored.
Declares lower-level string utility functions used when parsing messages.
int32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
septentrio_gnss_driver::RFStatus RfStatusMsg
ChannelStatus last_channelstatus_
Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored.
ExtSensorMeasMsg last_extsensmeas_
Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored.
septentrio_gnss_driver::MeasEpoch MeasEpochMsg
void assembleLocalizationUtm()
"Callback" function when constructing LocalizationMsg messages in UTM
MessageHandler(ROSaicNodeBase *node)
Constructor of the MessageHandler class.
ReceiverStatus last_receiverstatus_
Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored.
VelCovGeodeticMsg last_velcovgeodetic_
Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored.
ROSaicNodeBase * node_
Pointer to the node.
Struct for the SBF block "ReceiverStatus".
Derived class for parsing GSV messages.
INSNavCartMsg last_insnavcart_
Since LoclaizationEcef needs INSNavCart, incoming INSNavCart blocks need to be stored.
PosCovGeodeticMsg last_poscovgeodetic_
Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored.
void wait(Timestamp time_obj)
Waits according to time when reading from file.
void assembleOsnmaDiagnosticArray()
"Callback" function when constructing OSNMA DiagnosticArrayMsg messages
bool read_from_pcap
Whether or not we are reading from a PCAP file.
INSNavGeodMsg last_insnavgeod_
Since NavSatFix, GPSFix, Imu and Pose need INSNavGeod, incoming INSNavGeod blocks need to be stored.
void assembleTwist(bool fromIns=false)
"Callback" function when constructing TwistWithCovarianceStampedMsg messages
septentrio_gnss_driver::AttEuler AttEulerMsg