.. _program_listing_file__tmp_ws_src_ublox_ublox_gps_include_ublox_gps_ublox_firmware8.hpp: Program Listing for File ublox_firmware8.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/ublox_firmware8.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef UBLOX_GPS_UBLOX_FIRMWARE8_HPP #define UBLOX_GPS_UBLOX_FIRMWARE8_HPP #include #include #include #include #include #include #include #include #include #include #include namespace ublox_node { class UbloxFirmware8 : public UbloxFirmware7Plus { public: explicit UbloxFirmware8(const std::string & frame_id, std::shared_ptr updater, std::shared_ptr freq_diag, std::shared_ptr gnss, rclcpp::Node* node) : UbloxFirmware7Plus(frame_id, updater, freq_diag, gnss, node) { if (getRosBoolean(node_, "publish.nav.sat")) { nav_sat_pub_ = node->create_publisher("navstate", 1); } if (getRosBoolean(node_, "publish.mon.hw")) { mon_hw_pub_ = node->create_publisher("monhw", 1); } if (getRosBoolean(node_, "publish.rxm.rtcm")) { rxm_rtcm_pub_ = node->create_publisher("rxmrtcm", 1); } } void getRosParams() override; bool configureUblox(std::shared_ptr gps) override; void subscribe(std::shared_ptr gps) override; private: // Set from ROS parameters bool enable_galileo_{false}; bool enable_beidou_{false}; bool enable_imes_{false}; ublox_msgs::msg::CfgNMEA cfg_nmea_; bool clear_bbr_{false}; bool save_on_shutdown_{false}; rclcpp::Publisher::SharedPtr nav_sat_pub_; rclcpp::Publisher::SharedPtr mon_hw_pub_; rclcpp::Publisher::SharedPtr rxm_rtcm_pub_; }; } // namespace ublox_node #endif // UBLOX_GPS_UBLOX_FIRMWARE8_HPP