.. _program_listing_file__tmp_ws_src_ublox_ublox_gps_include_ublox_gps_adr_udr_product.hpp: Program Listing for File adr_udr_product.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/adr_udr_product.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef UBLOX_GPS_ADR_UDR_PRODUCT_HPP #define UBLOX_GPS_ADR_UDR_PRODUCT_HPP #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace ublox_node { class AdrUdrProduct final : public virtual ComponentInterface { public: explicit AdrUdrProduct(uint16_t nav_rate, uint16_t meas_rate, const std::string & frame_id, std::shared_ptr updater, rclcpp::Node* node); void getRosParams() override; bool configureUblox(std::shared_ptr gps) override; void initializeRosDiagnostics() override { // RCLCPP_WARN("ROS Diagnostics specific to u-blox ADR/UDR devices is %s", // "unimplemented. See AdrUdrProduct class in node.hpp & node.cpp."); } void subscribe(std::shared_ptr gps) override; private: bool use_adr_; sensor_msgs::msg::Imu imu_; sensor_msgs::msg::TimeReference t_ref_; void callbackEsfMEAS(const ublox_msgs::msg::EsfMEAS &m); rclcpp::Publisher::SharedPtr imu_pub_; rclcpp::Publisher::SharedPtr time_ref_pub_; rclcpp::Publisher::SharedPtr nav_att_pub_; rclcpp::Publisher::SharedPtr esf_ins_pub_; rclcpp::Publisher::SharedPtr esf_meas_pub_; rclcpp::Publisher::SharedPtr esf_raw_pub_; rclcpp::Publisher::SharedPtr esf_status_pub_; rclcpp::Publisher::SharedPtr hnr_pvt_pub_; uint16_t nav_rate_; uint16_t meas_rate_; std::string frame_id_; std::shared_ptr updater_; rclcpp::Node* node_; }; } // namespace ublox_node #endif // UBLOX_GPS_ADR_UDR_PRODUCT_HPP