Program Listing for File hpg_rov_product.hpp

Return to documentation for file (/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/hpg_rov_product.hpp)

#ifndef UBLOX_GPS_HPG_ROV_PRODUCT_HPP
#define UBLOX_GPS_HPG_ROV_PRODUCT_HPP

#include <memory>

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>

#include <ublox_msgs/msg/nav_relposned.hpp>

#include <ublox_gps/component_interface.hpp>
#include <ublox_gps/gps.hpp>
#include <ublox_gps/ublox_topic_diagnostic.hpp>

namespace ublox_node {

class HpgRovProduct final : public virtual ComponentInterface {
 public:
  // Constants for diagnostic updater
  const double kRtcmFreqMin = 1;
  const double kRtcmFreqMax = 10;
  const double kRtcmFreqTol = 0.1;
  const int kRtcmFreqWindow = 25;

  explicit HpgRovProduct(uint16_t nav_rate, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node);

  void getRosParams() override;

  bool configureUblox(std::shared_ptr<ublox_gps::Gps> gps) override;

  void initializeRosDiagnostics() override;

  void subscribe(std::shared_ptr<ublox_gps::Gps> gps) override;

 private:
  void carrierPhaseDiagnostics(
      diagnostic_updater::DiagnosticStatusWrapper& stat);

  void callbackNavRelPosNed(const ublox_msgs::msg::NavRELPOSNED &m);


  ublox_msgs::msg::NavRELPOSNED last_rel_pos_;


  uint8_t dgnss_mode_;

  std::unique_ptr<UbloxTopicDiagnostic> freq_rtcm_;

  rclcpp::Publisher<ublox_msgs::msg::NavRELPOSNED>::SharedPtr nav_rel_pos_ned_pub_;

  uint16_t nav_rate_;
  std::shared_ptr<diagnostic_updater::Updater> updater_;
  rclcpp::Node* node_;
};

}  // namespace ublox_node

#endif  // UBLOX_GPS_HPG_ROV_PRODUCT_HPP