.. _program_listing_file__tmp_ws_src_ublox_ublox_gps_include_ublox_gps_hpg_ref_product.hpp: Program Listing for File hpg_ref_product.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/hpg_ref_product.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef UBLOX_GPS_HPG_REF_PRODUCT_HPP #define UBLOX_GPS_HPG_REF_PRODUCT_HPP #include #include #include #include #include #include #include #include namespace ublox_node { class HpgRefProduct: public virtual ComponentInterface { public: constexpr static uint16_t kDefaultMeasPeriod = 250; explicit HpgRefProduct(uint16_t nav_rate, uint16_t meas_rate, std::shared_ptr updater, std::vector rtcms, rclcpp::Node* node); void getRosParams() override; bool configureUblox(std::shared_ptr gps) override; void initializeRosDiagnostics() override; void subscribe(std::shared_ptr gps) override; void callbackNavSvIn(const ublox_msgs::msg::NavSVIN& m); protected: void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat); bool setTimeMode(std::shared_ptr gps); ublox_msgs::msg::NavSVIN last_nav_svin_; uint8_t tmode3_; // TMODE3 = Fixed mode settings bool lla_flag_; std::vector arp_position_; std::vector arp_position_hp_; float fixed_pos_acc_; // Settings for TMODE3 = Survey-in bool svin_reset_; uint32_t sv_in_min_dur_; float sv_in_acc_lim_; enum { INIT, FIXED, DISABLED, SURVEY_IN, TIME } mode_{INIT}; rclcpp::Publisher::SharedPtr navsvin_pub_; uint16_t nav_rate_; uint16_t meas_rate_; std::shared_ptr updater_; std::vector rtcms_; std::shared_ptr gps_; rclcpp::Node* node_; }; } // namespace ublox_node #endif // UBLOX_GPS_HPG_REF_PRODUCT_HPP