Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
ublox_node::UbloxNode Class Reference

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

#include <node.h>

Inheritance diagram for ublox_node::UbloxNode:
Inheritance graph
[legend]

Public Member Functions

bool configureUblox ()
 Configure the device based on ROS parameters. More...
 
void getRosParams ()
 Get the node parameters from the ROS Parameter Server. More...
 
void initializeRosDiagnostics ()
 Initialize the diagnostic updater and add the fix diagnostic. More...
 
void printInf (const ublox_msgs::Inf &m, uint8_t id)
 Print an INF message to the ROS console. More...
 
void subscribe ()
 Subscribe to all requested u-blox messages. More...
 
 UbloxNode ()
 Initialize and run the u-blox node. More...
 

Static Public Attributes

static constexpr float kDiagnosticPeriod = 0.2
 [s] 5Hz diagnostic period More...
 
static constexpr double kFixFreqTol = 0.15
 Tolerance for Fix topic frequency as percentage of target frequency. More...
 
static constexpr double kFixFreqWindow = 10
 Window [num messages] for Fix Frequency Diagnostic. More...
 
static constexpr double kPollDuration = 1.0
 how often (in seconds) to call poll messages More...
 
static constexpr double kTimeStampStatusMin = 0
 Minimum Time Stamp Status for fix frequency diagnostic. More...
 

Private Member Functions

void addFirmwareInterface ()
 Add the interface for firmware specific configuration, subscribers, & diagnostics. This assumes the protocol_version_ has been set. More...
 
void addProductInterface (std::string product_category, std::string ref_rov="")
 Add the interface which is used for product category configuration, subscribers, & diagnostics. More...
 
void configureInf ()
 Configure INF messages, call after subscribe. More...
 
void initialize ()
 Initialize the U-Blox node. Configure the U-Blox and subscribe to messages. More...
 
void initializeIo ()
 Initialize the I/O handling. More...
 
void pollMessages (const ros::TimerEvent &event)
 Poll messages from the U-Blox device. More...
 
void processMonVer ()
 Process the MonVer message and add firmware and product components. More...
 
bool resetDevice ()
 Send a reset message the u-blox device & re-initialize the I/O. More...
 
void shutdown ()
 Shutdown the node. Closes the serial port. More...
 

Private Attributes

uint32_t baudrate_
 UART1 baudrate. More...
 
ublox_msgs::CfgDAT cfg_dat_
 User-defined Datum. More...
 
std::vector< boost::shared_ptr< ComponentInterface > > components_
 The u-blox node components. More...
 
std::string device_
 Device port. More...
 
uint8_t dmodel_
 Set from dynamic model string. More...
 
uint8_t dr_limit_
 Dead reckoning limit parameter. More...
 
std::string dynamic_model_
 dynamic model type More...
 
bool enable_ppp_
 Whether or not to enable PPP (advanced setting) More...
 
bool enable_sbas_
 Whether or not to enable SBAS. More...
 
std::string fix_mode_
 Fix mode type. More...
 
uint8_t fmode_
 Set from fix mode string. More...
 
ublox_msgs::CfgCFG load_
 Parameters to load from non-volatile memory during configuration. More...
 
uint8_t max_sbas_
 Max SBAS parameter (see CfgSBAS message) More...
 
float protocol_version_ = 0
 Determined From Mon VER. More...
 
double rate_
 The measurement rate in Hz. More...
 
RawDataStreamPa rawDataStreamPa_
 raw data stream logging More...
 
ublox_msgs::CfgCFG save_
 Parameters to save to non-volatile memory after configuration. More...
 
uint8_t sbas_usage_
 SBAS Usage parameter (see CfgSBAS message) More...
 
bool set_dat_
 If true, set configure the User-Defined Datum. More...
 
bool set_usb_
 Whether to configure the USB port. More...
 
uint8_t tim_rate_
 rate for TIM-TM2 More...
 
uint16_t uart_in_
 UART in protocol (see CfgPRT message for constants) More...
 
uint16_t uart_out_
 UART out protocol (see CfgPRT message for constants) More...
 
uint16_t usb_in_
 USB in protocol (see CfgPRT message for constants) More...
 
uint16_t usb_out_
 USB out protocol (see CfgPRT message for constants) More...
 
uint16_t usb_tx_
 USB TX Ready Pin configuration (see CfgPRT message for constants) More...
 

Detailed Description

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.

Definition at line 488 of file node.h.

Constructor & Destructor Documentation

UbloxNode::UbloxNode ( )

Initialize and run the u-blox node.

Definition at line 90 of file node.cpp.

Member Function Documentation

void UbloxNode::addFirmwareInterface ( )
private

Add the interface for firmware specific configuration, subscribers, & diagnostics. This assumes the protocol_version_ has been set.

Definition at line 94 of file node.cpp.

void UbloxNode::addProductInterface ( std::string  product_category,
std::string  ref_rov = "" 
)
private

Add the interface which is used for product category configuration, subscribers, & diagnostics.

Parameters
theproduct category, i.e. SPG, HPG, ADR, UDR, TIM, or FTS.
forHPG/TIM products, this value is either REF or ROV, for other products this string is empty

Definition at line 114 of file node.cpp.

void UbloxNode::configureInf ( )
private

Configure INF messages, call after subscribe.

Definition at line 492 of file node.cpp.

bool UbloxNode::configureUblox ( )
virtual

Configure the device based on ROS parameters.

Returns
true if configured successfully

Implements ublox_node::ComponentInterface.

Definition at line 420 of file node.cpp.

void UbloxNode::getRosParams ( )
virtual

Get the node parameters from the ROS Parameter Server.

Implements ublox_node::ComponentInterface.

Definition at line 135 of file node.cpp.

void UbloxNode::initialize ( )
private

Initialize the U-Blox node. Configure the U-Blox and subscribe to messages.

Definition at line 551 of file node.cpp.

void UbloxNode::initializeIo ( )
private

Initialize the I/O handling.

Definition at line 523 of file node.cpp.

void UbloxNode::initializeRosDiagnostics ( )
virtual

Initialize the diagnostic updater and add the fix diagnostic.

Implements ublox_node::ComponentInterface.

Definition at line 340 of file node.cpp.

void UbloxNode::pollMessages ( const ros::TimerEvent event)
private

Poll messages from the U-Blox device.

Parameters
eventa timer indicating how often to poll the messages

Definition at line 232 of file node.cpp.

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

Print an INF message to the ROS console.

Definition at line 247 of file node.cpp.

void UbloxNode::processMonVer ( )
private

Process the MonVer message and add firmware and product components.

Determines the protocol version, product type and supported GNSS.

Definition at line 355 of file node.cpp.

bool ublox_node::UbloxNode::resetDevice ( )
private

Send a reset message the u-blox device & re-initialize the I/O.

Returns
true if reset was successful, false otherwise.
void UbloxNode::shutdown ( )
private

Shutdown the node. Closes the serial port.

Definition at line 584 of file node.cpp.

void UbloxNode::subscribe ( )
virtual

Subscribe to all requested u-blox messages.

Implements ublox_node::ComponentInterface.

Definition at line 258 of file node.cpp.

Member Data Documentation

uint32_t ublox_node::UbloxNode::baudrate_
private

UART1 baudrate.

Definition at line 612 of file node.h.

ublox_msgs::CfgDAT ublox_node::UbloxNode::cfg_dat_
private

User-defined Datum.

Definition at line 631 of file node.h.

std::vector<boost::shared_ptr<ComponentInterface> > ublox_node::UbloxNode::components_
private

The u-blox node components.

The node will call the functions in these interfaces for each object in the vector.

Definition at line 596 of file node.h.

std::string ublox_node::UbloxNode::device_
private

Device port.

Definition at line 602 of file node.h.

uint8_t ublox_node::UbloxNode::dmodel_
private

Set from dynamic model string.

Definition at line 608 of file node.h.

uint8_t ublox_node::UbloxNode::dr_limit_
private

Dead reckoning limit parameter.

Definition at line 641 of file node.h.

std::string ublox_node::UbloxNode::dynamic_model_
private

dynamic model type

Definition at line 604 of file node.h.

bool ublox_node::UbloxNode::enable_ppp_
private

Whether or not to enable PPP (advanced setting)

Definition at line 635 of file node.h.

bool ublox_node::UbloxNode::enable_sbas_
private

Whether or not to enable SBAS.

Definition at line 633 of file node.h.

std::string ublox_node::UbloxNode::fix_mode_
private

Fix mode type.

Definition at line 606 of file node.h.

uint8_t ublox_node::UbloxNode::fmode_
private

Set from fix mode string.

Definition at line 610 of file node.h.

constexpr float ublox_node::UbloxNode::kDiagnosticPeriod = 0.2
static

[s] 5Hz diagnostic period

Definition at line 494 of file node.h.

constexpr double ublox_node::UbloxNode::kFixFreqTol = 0.15
static

Tolerance for Fix topic frequency as percentage of target frequency.

Definition at line 496 of file node.h.

constexpr double ublox_node::UbloxNode::kFixFreqWindow = 10
static

Window [num messages] for Fix Frequency Diagnostic.

Definition at line 498 of file node.h.

constexpr double ublox_node::UbloxNode::kPollDuration = 1.0
static

how often (in seconds) to call poll messages

Definition at line 491 of file node.h.

constexpr double ublox_node::UbloxNode::kTimeStampStatusMin = 0
static

Minimum Time Stamp Status for fix frequency diagnostic.

Definition at line 500 of file node.h.

ublox_msgs::CfgCFG ublox_node::UbloxNode::load_
private

Parameters to load from non-volatile memory during configuration.

Definition at line 643 of file node.h.

uint8_t ublox_node::UbloxNode::max_sbas_
private

Max SBAS parameter (see CfgSBAS message)

Definition at line 639 of file node.h.

float ublox_node::UbloxNode::protocol_version_ = 0
private

Determined From Mon VER.

Definition at line 599 of file node.h.

double ublox_node::UbloxNode::rate_
private

The measurement rate in Hz.

Definition at line 627 of file node.h.

RawDataStreamPa ublox_node::UbloxNode::rawDataStreamPa_
private

raw data stream logging

Definition at line 650 of file node.h.

ublox_msgs::CfgCFG ublox_node::UbloxNode::save_
private

Parameters to save to non-volatile memory after configuration.

Definition at line 645 of file node.h.

uint8_t ublox_node::UbloxNode::sbas_usage_
private

SBAS Usage parameter (see CfgSBAS message)

Definition at line 637 of file node.h.

bool ublox_node::UbloxNode::set_dat_
private

If true, set configure the User-Defined Datum.

Definition at line 629 of file node.h.

bool ublox_node::UbloxNode::set_usb_
private

Whether to configure the USB port.

Set to true if usb_in & usb_out parameters are set

Definition at line 621 of file node.h.

uint8_t ublox_node::UbloxNode::tim_rate_
private

rate for TIM-TM2

Definition at line 647 of file node.h.

uint16_t ublox_node::UbloxNode::uart_in_
private

UART in protocol (see CfgPRT message for constants)

Definition at line 614 of file node.h.

uint16_t ublox_node::UbloxNode::uart_out_
private

UART out protocol (see CfgPRT message for constants)

Definition at line 616 of file node.h.

uint16_t ublox_node::UbloxNode::usb_in_
private

USB in protocol (see CfgPRT message for constants)

Definition at line 623 of file node.h.

uint16_t ublox_node::UbloxNode::usb_out_
private

USB out protocol (see CfgPRT message for constants)

Definition at line 625 of file node.h.

uint16_t ublox_node::UbloxNode::usb_tx_
private

USB TX Ready Pin configuration (see CfgPRT message for constants)

Definition at line 618 of file node.h.


The documentation for this class was generated from the following files:


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:52