Template Class UbloxFirmware7Plus

Inheritance Relationships

Base Type

Class Documentation

template<typename NavPVT>
class UbloxFirmware7Plus : public ublox_node::UbloxFirmware

Public Functions

inline explicit UbloxFirmware7Plus(const std::string &frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, std::shared_ptr<FixDiagnostic> freq_diag, std::shared_ptr<Gnss> gnss, rclcpp::Node *node)
inline void callbackNavPvt(const NavPVT &m)

Publish a NavSatFix and TwistWithCovarianceStamped messages.

If a fixed carrier phase solution is available, the NavSatFix status is set to GBAS fixed. If NavPVT publishing is enabled, the message is published. This function also calls the ROS diagnostics updater.

Parameters:

m – the message to publish

Protected Functions

inline virtual void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat) override

Update the fix diagnostics from Nav PVT message.

Protected Attributes

NavPVT last_nav_pvt_

The last received NavPVT message.

bool enable_gps_ = {false}

Whether or not to enable GPS.

bool enable_glonass_ = {false}

Whether or not to enable GLONASS.

bool enable_qzss_ = {false}

Whether or not to enable QZSS.

uint32_t qzss_sig_cfg_ = {0}

The QZSS Signal configuration, see CfgGNSS message.

rclcpp::Publisher<NavPVT>::SharedPtr nav_pvt_pub_
rclcpp::Publisher<sensor_msgs::msg::NavSatFix>::SharedPtr fix_pub_
rclcpp::Publisher<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr vel_pub_
std::string frame_id_
std::shared_ptr<FixDiagnostic> freq_diag_