Program Listing for File ublox_topic_diagnostic.hpp

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

#ifndef UBLOX_GPS_UBLOX_TOPIC_DIAGNOSTIC_HPP
#define UBLOX_GPS_UBLOX_TOPIC_DIAGNOSTIC_HPP

#include <memory>
#include <string>

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <diagnostic_updater/update_functions.hpp>

namespace ublox_node {

struct UbloxTopicDiagnostic {
  UbloxTopicDiagnostic() = default;

  // Must not copy this struct (would confuse FrequencyStatusParam pointers)
  UbloxTopicDiagnostic(UbloxTopicDiagnostic &&c) = delete;
  UbloxTopicDiagnostic &operator=(UbloxTopicDiagnostic &&c) = delete;
  UbloxTopicDiagnostic(const UbloxTopicDiagnostic &c) = delete;
  UbloxTopicDiagnostic &operator=(const UbloxTopicDiagnostic &c) = delete;

  ~UbloxTopicDiagnostic() = default;

  explicit UbloxTopicDiagnostic(const std::string & topic, double freq_tol, int freq_window,
                                uint16_t nav_rate, uint16_t meas_rate, std::shared_ptr<diagnostic_updater::Updater> updater) {
    const double target_freq = 1.0 / (meas_rate * 1e-3 * nav_rate); // Hz
    min_freq = target_freq;
    max_freq = target_freq;
    diagnostic_updater::FrequencyStatusParam freq_param(&min_freq, &max_freq,
                                                        freq_tol, freq_window);
    diagnostic = std::make_shared<diagnostic_updater::HeaderlessTopicDiagnostic>(topic,
                                                                                 *updater,
                                                                                 freq_param);
  }

  explicit UbloxTopicDiagnostic(const std::string & topic, double freq_min, double freq_max,
                                double freq_tol, int freq_window, std::shared_ptr<diagnostic_updater::Updater> updater) {
    min_freq = freq_min;
    max_freq = freq_max;
    diagnostic_updater::FrequencyStatusParam freq_param(&min_freq, &max_freq,
                                                        freq_tol, freq_window);
    diagnostic = std::make_shared<diagnostic_updater::HeaderlessTopicDiagnostic>(topic,
                                                                                 *updater,
                                                                                 freq_param);
  }

  std::shared_ptr<diagnostic_updater::HeaderlessTopicDiagnostic> diagnostic;
  double min_freq{0.0};
  double max_freq{0.0};
};

}  // namespace ublox_node

#endif