Class HpgRovProduct

Inheritance Relationships

Base Type

Class Documentation

class HpgRovProduct : public virtual ublox_node::ComponentInterface

Implements functions for High Precision GNSS Rover devices.

Public Functions

explicit HpgRovProduct(uint16_t nav_rate, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node *node)
virtual void getRosParams() override

Get the ROS parameters specific to the Rover configuration.

Get the DGNSS mode.

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

Configure rover settings.

Configure the DGNSS mode.

Returns:

true if configured correctly, false otherwise

virtual void initializeRosDiagnostics() override

Add diagnostic updaters for rover GNSS status, including status of RTCM messages.

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

Subscribe to Rover messages, such as NavRELPOSNED.

Public Members

const double kRtcmFreqMin = 1

Diagnostic updater: RTCM topic frequency min [Hz].

const double kRtcmFreqMax = 10

Diagnostic updater: RTCM topic frequency max [Hz].

const double kRtcmFreqTol = 0.1

Diagnostic updater: RTCM topic frequency tolerance [%].

const int kRtcmFreqWindow = 25

Diagnostic updater: RTCM topic frequency window [num messages].