Class UbloxFirmware8

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class UbloxFirmware8 : public ublox_node::UbloxFirmware7Plus<ublox_msgs::msg::NavPVT>

Implements functions for firmware version 8.

Subclassed by ublox_node::UbloxFirmware9

Public Functions

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

Get the ROS parameters specific to firmware version 8.

Get the GNSS, NMEA, and UPD settings.

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

Configure settings specific to firmware 8 based on ROS parameters.

Configure GNSS, if it is different from current settings. Configure the NMEA if desired by the user. It also may clear the flash memory based on the ROS parameters.

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

Subscribe to u-blox messages which are not generic to all firmware versions.

Subscribe to NavPVT, NavSAT, MonHW, and RxmRTCM messages based on user settings.

Protected Attributes

bool enable_galileo_ = {false}

Whether or not to enable the Galileo GNSS.

bool enable_beidou_ = {false}

Whether or not to enable the BeiDuo GNSS.

bool enable_imes_ = {false}

Whether or not to enable the IMES GNSS.

ublox_msgs::msg::CfgNMEA cfg_nmea_

Desired NMEA configuration.

bool clear_bbr_ = {false}

Whether to clear the flash memory during configuration.

bool save_on_shutdown_ = {false}