Go to the documentation of this file.
60 #ifndef NMEA_SYNC_BYTE_1
61 #define NMEA_SYNC_BYTE_1 0x24
63 #ifndef NMEA_SYNC_BYTE_2_1
65 #define NMEA_SYNC_BYTE_2_1 0x47
67 #ifndef NMEA_SYNC_BYTE_2_2
69 #define NMEA_SYNC_BYTE_2_2 0x50
71 #ifndef RESPONSE_SYNC_BYTE_1
73 #define RESPONSE_SYNC_BYTE_1 0x24
75 #ifndef RESPONSE_SYNC_BYTE_2
77 #define RESPONSE_SYNC_BYTE_2 0x52
79 #ifndef CARRIAGE_RETURN
81 #define CARRIAGE_RETURN 0x0D
85 #define LINE_FEED 0x0A
87 #ifndef RESPONSE_SYNC_BYTE_3
90 #define RESPONSE_SYNC_BYTE_3 0x3F
92 #ifndef CONNECTION_DESCRIPTOR_BYTE_1
95 #define CONNECTION_DESCRIPTOR_BYTE_1 0x49
97 #ifndef CONNECTION_DESCRIPTOR_BYTE_2
100 #define CONNECTION_DESCRIPTOR_BYTE_2 0x50
109 #include <boost/call_traits.hpp>
110 #include <boost/format.hpp>
111 #include <boost/math/constants/constants.hpp>
112 #include <boost/tokenizer.hpp>
122 #ifndef RX_MESSAGE_HPP
123 #define RX_MESSAGE_HPP
222 std::pair<uint16_t, TypeOfPVT_Enum> type_of_pvt_pairs[] = {
223 std::make_pair(
static_cast<uint16_t
>(0),
evNoPVT),
225 std::make_pair(
static_cast<uint16_t
>(2),
evDGPS),
226 std::make_pair(
static_cast<uint16_t
>(3),
evFixed),
227 std::make_pair(
static_cast<uint16_t
>(4),
evRTKFixed),
228 std::make_pair(
static_cast<uint16_t
>(5),
evRTKFloat),
229 std::make_pair(
static_cast<uint16_t
>(6),
evSBAS),
232 std::make_pair(
static_cast<uint16_t
>(10),
evPPP)};
238 std::pair<std::string, RxID_Enum> rx_id_pairs[] = {
243 std::make_pair(
"PoseWithCovarianceStamped",
245 std::make_pair(
"INSPoseWithCovarianceStamped",
247 std::make_pair(
"$GPGGA",
evGPGGA),
248 std::make_pair(
"$GPRMC",
evGPRMC),
249 std::make_pair(
"$GPGSA",
evGPGSA),
250 std::make_pair(
"$GPGSV",
evGPGSV),
251 std::make_pair(
"$GLGSV",
evGLGSV),
252 std::make_pair(
"$GAGSV",
evGAGSV),
261 std::make_pair(
"GPST",
evGPST),
264 std::make_pair(
"4001",
evDOP),
375 template <
typename M>
376 void publish(
const std::string& topic,
const M& msg);
388 bool read(std::string message_key,
bool search =
false);
562 typedef std::unordered_map<std::string, RxID_Enum>
RxIDMap;
720 bool allTrue(std::vector<bool>& vec, uint32_t
id);
760 #endif // for RX_MESSAGE_HPP
bool atteuler_has_arrived_pose_
bool attcoveuler_has_arrived_gpsfix_
std::size_t count_
Number of unread bytes in the buffer.
Struct for the SBF block "QualityInd".
bool isNMEA()
Determines whether data_ currently points to an NMEA message.
bool insnavgeod_has_arrived_localization_
Derived class for parsing RMC messages.
void publishTf(const LocalizationUtmMsg &msg)
Publishing function.
NavSatFixMsg NavSatFixCallback()
"Callback" function when constructing NavSatFix messages
bool atteuler_has_arrived_gpsfix_
std::size_t messageSize()
RxIDMap rx_id_map
All instances of the RxMessage class shall have access to the map without reinitializing it,...
bool pvtgeodetic_has_arrived_pose_
bool pvtgeodetic_has_arrived_gpsfix_
Derived class for parsing GGA messages.
Timestamp timestampSBF(const uint8_t *data, bool use_gnss_time)
Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmit...
std::shared_ptr< std::string > fixedUtmZone_
Fixed UTM zone.
sensor_msgs::NavSatFix NavSatFixMsg
AttEulerMsg last_atteuler_
Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored.
int8_t current_leap_seconds_
Current leap seconds as received, do not use value is -128.
geometry_msgs::TwistWithCovarianceStamped TwistWithCovarianceStampedMsg
std::size_t message_size_
Helps to determine size of response message / NMEA message / SBF block.
uint16_t getBlockLength()
Gets the length of the SBF block.
const uint8_t * data_
Pointer to the buffer of messages.
bool found()
Has an NMEA message, SBF block or command reply been found in the buffer?
void next()
Goes to the start of the next message based on the calculated length of current message.
Declares the functions to compute and validate the CRC of a buffer.
ReceiverStatus last_receiverstatus_
Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored.
TypeOfPVTMap type_of_pvt_map
All instances of the RxMessage class shall have access to the map without reinitializing it,...
bool gnss_pose_complete(uint32_t id)
Wether all blocks from GNSS have arrived for Pose Message.
septentrio_gnss_driver::VelCovGeodetic VelCovGeodeticMsg
ImuMsg ImuCallback()
"Callback" function when constructing ImuMsg messages
INSNavGeodMsg last_insnavgeod_
Since NavSatFix, GPSFix, Imu and Pose. need INSNavGeod, incoming INSNavGeod blocks need to be stored.
std::size_t getCount()
Returns the count_ variable.
bool found_
Whether or not a message has been found.
This class is the base class for abstraction.
std::unordered_map< std::string, RxID_Enum > RxIDMap
bool gnss_gpsfix_complete(uint32_t id)
Wether all blocks from GNSS have arrived for GpsFix Message.
Settings * settings_
Settings struct.
AttCovEulerMsg last_attcoveuler_
Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored.
bool isConnectionDescriptor()
bool ins_navsatfix_complete(uint32_t id)
Wether all blocks from INS have arrived for NavSatFix Message.
bool poscovgeodetic_has_arrived_gpsfix_
septentrio_gnss_driver::PVTGeodetic PVTGeodeticMsg
septentrio_gnss_driver::PosCovGeodetic PosCovGeodeticMsg
bool insnavgeod_has_arrived_pose_
const uint8_t * search()
Searches the buffer for the beginning of the next message (NMEA or SBF)
bool pvtgeodetic_has_arrived_navsatfix_
@ evINSPoseWithCovarianceStamped
bool insnavgeod_has_arrived_navsatfix_
bool channelstatus_has_arrived_gpsfix_
ROSaicNodeBase * node_
Pointer to the node.
nav_msgs::Odometry LocalizationUtmMsg
Declares lower-level string utility functions used when parsing messages.
void wait(Timestamp time_obj)
Waits according to time when reading from file.
bool receiverstatus_has_arrived_diagnostics_
MeasEpochMsg last_measepoch_
Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored.
gps_common::GPSFix GPSFixMsg
bool crc_check_
Whether the CRC check as evaluated in the read() method was successful or not is stored here.
GPSFixMsg GPSFixCallback()
"Callback" function when constructing GPSFix messages
const uint8_t * getPosBuffer()
Gets the current position in the read buffer.
septentrio_gnss_driver::AttCovEuler AttCovEulerMsg
QualityInd last_qualityind_
Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored.
bool diagnostics_complete(uint32_t id)
Wether all blocks have arrived for Diagnostics Message.
bool ins_gpsfix_complete(uint32_t id)
Wether all blocks from INS have arrived for GpsFix Message.
std::unordered_map< uint16_t, TypeOfPVT_Enum > TypeOfPVTMap
septentrio_gnss_driver::INSNavGeod INSNavGeodMsg
void newData(Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
Put new data.
bool gnss_navsatfix_complete(uint32_t id)
Wether all blocks from GNSS have arrived for NavSatFix Message.
ChannelStatus last_channelstatus_
Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored.
DiagnosticArrayMsg DiagnosticArrayCallback()
"Callback" function when constructing DiagnosticArrayMsg messages
bool isSBF()
Determines whether data_ currently points to an SBF block.
Struct for the SBF block "DOP".
TwistWithCovarianceStampedMsg TwistCallback(bool fromIns=false)
"Callback" function when constructing TwistWithCovarianceStampedMsg messages
LocalizationUtmMsg LocalizationUtmCallback()
"Callback" function when constructing LocalizationUtmMsg messages
bool poscovgeodetic_has_arrived_navsatfix_
ExtSensorMeasMsg last_extsensmeas_
Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored.
PVTGeodeticMsg last_pvtgeodetic_
Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored.
septentrio_gnss_driver::ExtSensorMeas ExtSensorMeasMsg
Struct for the SBF block "ChannelStatus".
Timestamp recvTimestamp_
Timestamp of receiving buffer.
RxMessage(ROSaicNodeBase *node, Settings *settings)
Constructor of the RxMessage class.
Derived class for parsing GSA messages.
PoseWithCovarianceStampedMsg PoseWithCovarianceStampedCallback()
"Callback" function when constructing PoseWithCovarianceStamped messages
Struct for the SBF block "ReceiverSetup".
bool isResponse()
Determines whether data_ currently points to an NMEA message.
uint32_t count_gpsfix_
Number of times the GPSFixMsg message has been published.
bool read(std::string message_key, bool search=false)
Performs the CRC check (if SBF) and publishes ROS messages.
bool insnavgeod_has_arrived_gpsfix_
@ evPoseWithCovarianceStamped
PosCovGeodeticMsg last_poscovgeodetic_
Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored.
bool attcoveuler_has_arrived_pose_
DOP last_dop_
Since GPSFix needs DOP, incoming DOP blocks need to be stored.
bool allTrue(std::vector< bool > &vec, uint32_t id)
Wether all elements are true.
bool ins_pose_complete(uint32_t id)
Wether all blocks from INS have arrived for Pose Message.
septentrio_gnss_driver::MeasEpoch MeasEpochMsg
bool dop_has_arrived_gpsfix_
For GPSFix: Whether the DOP block of the current epoch has arrived or not.
const uint8_t * getEndBuffer()
Gets the end position in the read buffer.
bool isMessage(const uint16_t ID)
Determines whether data_ points to the SBF block with ID "ID", e.g. 5003.
void publish(const std::string &topic, const M &msg)
Publishing function.
bool measepoch_has_arrived_gpsfix_
bool ins_localization_complete(uint32_t id)
Wether all blocks have arrived for Localization Message.
Struct for the SBF block "ReceiverStatus".
Derived class for parsing GSV messages.
Can search buffer for messages, read/parse them, and so on.
bool velcovgeodetic_has_arrived_gpsfix_
bool qualityind_has_arrived_diagnostics_
ReceiverSetup last_receiversetup_
Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored.
bool poscovgeodetic_has_arrived_pose_
geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStampedMsg
diagnostic_msgs::DiagnosticArray DiagnosticArrayMsg
VelCovGeodeticMsg last_velcovgeodetic_
Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored.
septentrio_gnss_driver::AttEuler AttEulerMsg