Class NovatelMessageExtractor

Class Documentation

class NovatelMessageExtractor

Public Functions

explicit NovatelMessageExtractor(rclcpp::Logger logger)
bool ExtractCompleteMessages(const std::string &input, std::vector<NmeaSentence> &nmea_sentences, std::vector<NovatelSentence> &novatel_sentences, std::vector<BinaryMessage> &binary_messages, std::string &remaining, bool keep_nmea_container = false)

Extracts messages from a buffer of NovAtel data.

This will search through the “input” string for any valid NMEA or NovAtel ASCII messages as well as any binary NovAtel messages, place them into the provided containers, and also provide any leftover bytes at the end of the buffer that were not part of a valid sentence.

Parameters:
  • input[in] A buffer of data to search for messages

  • nmea_sentences[out] NMEA sentences found in the buffer

  • novatel_sentences[out] ASCII NovAtel sentences found in the buffer

  • binary_messages[out] Binary NovAtel message found in the buffer

  • remaining[out] Any bytes left after the last complete sentence in the buffer

  • keep_nmea_container[in] “true” to preserve message begin & end markers around parsed NMEA sentences

Returns:

false if there were any errors parsing sentences

double GetMostRecentUtcTime(const std::vector<NmeaSentence> &sentences)

Iterates through the provided messages to find the first GPGGA or GPRMC message with a valid UTC time, then returns it.

Parameters:

sentences[in] A list of NMEA sentences to search for UTC times.

Returns:

The UTC time in seconds, if found; 0 if not found.

void GetGpsFixMessage(const novatel_gps_msgs::msg::Gprmc &gprmc, const novatel_gps_msgs::msg::Gpgga &gpgga, const gps_msgs::msg::GPSFix::UniquePtr &gps_fix)

Combines data receives in GPRMC and GPGGA message to produce a gps_msgs/GPSFixPtr ROS message.

Parameters:
  • gprmc[in] A valid GPRMC message.

  • gpgga[in] A valid GPGGA message.

  • gps_fix[out] An initialised GPSFixPtr message must be provided; it will be filled in based on the provided GPRMC/GPGGA messages.