Class HpgRefProduct

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class HpgRefProduct : public virtual ublox_node::ComponentInterface

Implements functions for High Precision GNSS Reference station devices.

Subclassed by ublox_node::HpPosRecProduct

Public Functions

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)
virtual void getRosParams() override

Get the ROS parameters specific to the Reference Station configuration.

Get the TMODE3 settings, the parameters it gets depends on the tmode3 parameter. For example, it will get survey-in parameters if the tmode3 parameter is set to survey in or it will get the fixed parameters if it is set to fixed.

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

Configure the u-blox Reference Station settings.

Configure the TMODE3 settings and sets the internal state based on the TMODE3 status. If the TMODE3 is set to fixed, it will configure the RTCM messages.

Returns:

true if configured correctly, false otherwise

virtual void initializeRosDiagnostics() override

Add diagnostic updaters for the TMODE3 status.

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

Subscribe to u-blox Reference Station messages.

Subscribe to NavSVIN messages based on user parameters.

void callbackNavSvIn(const ublox_msgs::msg::NavSVIN &m)

Update the last received NavSVIN message and call diagnostic updater.

When the survey in finishes, it changes the measurement & navigation rate to the user configured values and enables the user configured RTCM messages. Publish received Nav SVIN messages if enabled.

Parameters:

m – the message to process

Public Static Attributes

static constexpr uint16_t kDefaultMeasPeriod = 250

Default measurement period for HPG devices.

Protected Types

Status of device time mode.

Values:

enumerator INIT

Initialization mode (before configuration)

enumerator FIXED

Fixed mode (should switch to time mode almost immediately)

enumerator DISABLED

Time mode disabled.

enumerator SURVEY_IN

Survey-In mode.

enumerator TIME

Time mode, after survey-in or after configuring fixed mode.

Protected Functions

void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)

Update the TMODE3 diagnostics.

Updates the status of the survey-in if in survey-in mode or the RTCM messages if in time mode.

bool setTimeMode(std::shared_ptr<ublox_gps::Gps> gps)

Set the device mode to time mode (internal state variable).

Configure the RTCM messages and measurement and navigation rate.

Protected Attributes

ublox_msgs::msg::NavSVIN last_nav_svin_

The last received Nav SVIN message.

uint8_t tmode3_

TMODE3 to set, such as disabled, survey-in, fixed.

bool lla_flag_

True if coordinates are in LLA, false if ECEF.

Used only for fixed mode

std::vector<double> arp_position_

Antenna Reference Point Position [m] or [deg].

Used only for fixed mode

std::vector<int8_t> arp_position_hp_

Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9].

Used only for fixed mode

float fixed_pos_acc_

Fixed Position Accuracy [m].

Used only for fixed mode

bool svin_reset_

Whether to always reset the survey-in during configuration.

If false, it only resets survey-in if there’s no fix and TMODE3 is disabled before configuration. This variable is used only if TMODE3 is set to survey-in.

uint32_t sv_in_min_dur_

Measurement period used during Survey-In [s].

This variable is used only if TMODE3 is set to survey-in.

float sv_in_acc_lim_

Survey in accuracy limit [m].

This variable is used only if TMODE3 is set to survey-in.

enum ublox_node::HpgRefProduct INIT

Status of device time mode.

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_