Program Listing for File hpg_ref_product.hpp
↰ Return to documentation for file (/tmp/ws/src/ublox/ublox_gps/include/ublox_gps/hpg_ref_product.hpp
)
#ifndef UBLOX_GPS_HPG_REF_PRODUCT_HPP
#define UBLOX_GPS_HPG_REF_PRODUCT_HPP
#include <memory>
#include <vector>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>
#include <ublox_msgs/msg/nav_svin.hpp>
#include <ublox_gps/component_interface.hpp>
#include <ublox_gps/gps.hpp>
#include <ublox_gps/rtcm.hpp>
namespace ublox_node {
class HpgRefProduct: public virtual ComponentInterface {
public:
constexpr static uint16_t kDefaultMeasPeriod = 250;
explicit HpgRefProduct(uint16_t nav_rate, uint16_t meas_rate, std::shared_ptr<diagnostic_updater::Updater> updater, std::vector<ublox_gps::Rtcm> rtcms, 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;
void callbackNavSvIn(const ublox_msgs::msg::NavSVIN& m);
protected:
void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
bool setTimeMode(std::shared_ptr<ublox_gps::Gps> gps);
ublox_msgs::msg::NavSVIN last_nav_svin_;
uint8_t tmode3_;
// TMODE3 = Fixed mode settings
bool lla_flag_;
std::vector<double> arp_position_;
std::vector<int8_t> arp_position_hp_;
float fixed_pos_acc_;
// Settings for TMODE3 = Survey-in
bool svin_reset_;
uint32_t sv_in_min_dur_;
float sv_in_acc_lim_;
enum {
INIT,
FIXED,
DISABLED,
SURVEY_IN,
TIME
} mode_{INIT};
rclcpp::Publisher<ublox_msgs::msg::NavSVIN>::SharedPtr navsvin_pub_;
uint16_t nav_rate_;
uint16_t meas_rate_;
std::shared_ptr<diagnostic_updater::Updater> updater_;
std::vector<ublox_gps::Rtcm> rtcms_;
std::shared_ptr<ublox_gps::Gps> gps_;
rclcpp::Node* node_;
};
} // namespace ublox_node
#endif // UBLOX_GPS_HPG_REF_PRODUCT_HPP