Class UbloxNode

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class UbloxNode : public rclcpp::Node

This class represents u-blox ROS node for all firmware and product versions.

It loads the user parameters, configures the u-blox device, subscribes to u-blox messages, and configures the device hardware. Functionality specific to a given product or firmware version, etc. should NOT be implemented in this class. Instead, the user should add the functionality to the appropriate implementation of ComponentInterface. If necessary, the user should create a class which implements u-blox interface, then add a pointer to an instance of the class to the components vector. The UbloxNode calls the public methods of ComponentInterface for each element in the components vector.

Public Functions

explicit UbloxNode(const rclcpp::NodeOptions &options)

Initialize and run the u-blox node.

~UbloxNode() override
UbloxNode(UbloxNode &&c) = delete
UbloxNode &operator=(UbloxNode &&c) = delete
UbloxNode(const UbloxNode &c) = delete
UbloxNode &operator=(const UbloxNode &c) = delete
void getRosParams()

Get the node parameters from the ROS Parameter Server.

bool configureUblox()

Configure the device based on ROS parameters.

Returns:

true if configured successfully

void subscribe()

Subscribe to all requested u-blox messages.

void initializeRosDiagnostics()

Initialize the diagnostic updater and add the fix diagnostic.

void printInf(const ublox_msgs::msg::Inf &m, uint8_t id)

Print an INF message to the ROS console.

Public Members

const float kDiagnosticPeriod = 0.2

[s] 5Hz diagnostic period

const double kFixFreqTol = 0.15

Tolerance for Fix topic frequency as percentage of target frequency.

const double kFixFreqWindow = 10

Window [num messages] for Fix Frequency Diagnostic.

const double kTimeStampStatusMin = 0

Minimum Time Stamp Status for fix frequency diagnostic.

Public Static Attributes

static constexpr int kResetWait = 10

How long to wait during I/O reset [s].

static constexpr double kKeepAlivePeriod = 10.0

How often (in seconds) to send keep-alive message.

static constexpr double kPollDuration = 1.0

How often (in seconds) to call poll messages.