.. _program_listing_file__tmp_ws_src_ublox_ublox_gps_include_ublox_gps_ublox_firmware6.hpp: Program Listing for File ublox_firmware6.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/ublox_firmware6.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef UBLOX_GPS_UBLOX_FIRMWARE6_HPP #define UBLOX_GPS_UBLOX_FIRMWARE6_HPP #include #include #include #include #include #include #include #include #include #include #include #include #include namespace ublox_node { class UbloxFirmware6 final : public UbloxFirmware { public: explicit UbloxFirmware6(const std::string & frame_id, std::shared_ptr updater, std::shared_ptr freq_diag, std::shared_ptr gnss, rclcpp::Node* node); void getRosParams() override; bool configureUblox(std::shared_ptr gps) override; void subscribe(std::shared_ptr gps) override; protected: void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat) override; private: void callbackNavPosLlh(const ublox_msgs::msg::NavPOSLLH& m); void callbackNavVelNed(const ublox_msgs::msg::NavVELNED& m); void callbackNavSol(const ublox_msgs::msg::NavSOL& m); ublox_msgs::msg::NavPOSLLH last_nav_pos_; ublox_msgs::msg::NavVELNED last_nav_vel_; ublox_msgs::msg::NavSOL last_nav_sol_; sensor_msgs::msg::NavSatFix fix_; geometry_msgs::msg::TwistWithCovarianceStamped velocity_; ublox_msgs::msg::CfgNMEA6 cfg_nmea_; rclcpp::Publisher::SharedPtr nav_pos_llh_pub_; rclcpp::Publisher::SharedPtr fix_pub_; rclcpp::Publisher::SharedPtr nav_vel_ned_pub_; rclcpp::Publisher::SharedPtr vel_pub_; rclcpp::Publisher::SharedPtr nav_sol_pub_; rclcpp::Publisher::SharedPtr nav_svinfo_pub_; rclcpp::Publisher::SharedPtr mon_hw_pub_; std::string frame_id_; std::shared_ptr freq_diag_; }; } // namespace ublox_node #endif // UBLOX_GPS_UBLOX_FIRMWARE6_HPP