.. _program_listing_file__tmp_ws_src_ublox_ublox_gps_include_ublox_gps_raw_data_product.hpp: Program Listing for File raw_data_product.hpp ============================================= |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/raw_data_product.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef UBLOX_GPS_RAW_DATA_PRODUCT_HPP #define UBLOX_GPS_RAW_DATA_PRODUCT_HPP #include #include #include #include #include #include #include #include #include #include #include namespace ublox_node { class RawDataProduct final : public virtual ComponentInterface { public: const double kRtcmFreqTol = 0.15; const int kRtcmFreqWindow = 25; explicit RawDataProduct(uint16_t nav_rate, uint16_t meas_rate, std::shared_ptr updater, rclcpp::Node* node); void getRosParams() override {} bool configureUblox(std::shared_ptr gps) override { (void)gps; return true; } void initializeRosDiagnostics() override; void subscribe(std::shared_ptr gps) override; private: std::vector > freq_diagnostics_; rclcpp::Publisher::SharedPtr rxm_raw_pub_; rclcpp::Publisher::SharedPtr rxm_sfrb_pub_; rclcpp::Publisher::SharedPtr rxm_eph_pub_; rclcpp::Publisher::SharedPtr rxm_alm_pub_; uint16_t nav_rate_; uint16_t meas_rate_; std::shared_ptr updater_; rclcpp::Node* node_; }; } // namespace ublox_node #endif // UBLOX_GPS_RAW_DATA_PRODUCT_HPP