Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
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]

List of all members.

Public Member Functions

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

Static Public Attributes

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

Private Member Functions

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

Private Attributes

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

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 481 of file node.h.


Constructor & Destructor Documentation

Initialize and run the u-blox node.

Definition at line 85 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 89 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 105 of file node.cpp.

void UbloxNode::configureInf ( ) [private]

Configure INF messages, call after subscribe.

Definition at line 481 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 409 of file node.cpp.

void UbloxNode::getRosParams ( ) [virtual]

Get the node parameters from the ROS Parameter Server.

Implements ublox_node::ComponentInterface.

Definition at line 124 of file node.cpp.

void UbloxNode::initialize ( ) [private]

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

Definition at line 540 of file node.cpp.

void UbloxNode::initializeIo ( ) [private]

Initialize the I/O handling.

Definition at line 512 of file node.cpp.

Initialize the diagnostic updater and add the fix diagnostic.

Implements ublox_node::ComponentInterface.

Definition at line 329 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 221 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 236 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 344 of file node.cpp.

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 573 of file node.cpp.

void UbloxNode::subscribe ( ) [virtual]

Subscribe to all requested u-blox messages.

Implements ublox_node::ComponentInterface.

Definition at line 247 of file node.cpp.


Member Data Documentation

UART1 baudrate.

Definition at line 607 of file node.h.

ublox_msgs::CfgDAT ublox_node::UbloxNode::cfg_dat_ [private]

User-defined Datum.

Definition at line 626 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 591 of file node.h.

std::string ublox_node::UbloxNode::device_ [private]

Device port.

Definition at line 597 of file node.h.

uint8_t ublox_node::UbloxNode::dmodel_ [private]

Set from dynamic model string.

Definition at line 603 of file node.h.

Dead reckoning limit parameter.

Definition at line 636 of file node.h.

dynamic model type

Definition at line 599 of file node.h.

Whether or not to enable PPP (advanced setting)

Definition at line 630 of file node.h.

Whether or not to enable SBAS.

Definition at line 628 of file node.h.

std::string ublox_node::UbloxNode::fix_mode_ [private]

Fix mode type.

Definition at line 601 of file node.h.

uint8_t ublox_node::UbloxNode::fmode_ [private]

Set from fix mode string.

Definition at line 605 of file node.h.

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

[s] 5Hz diagnostic period

Definition at line 489 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 491 of file node.h.

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

Window [num messages] for Fix Frequency Diagnostic.

Definition at line 493 of file node.h.

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

how often (in seconds) to call poll messages

Definition at line 486 of file node.h.

constexpr int ublox_node::UbloxNode::kResetWait = 10 [static]

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

Definition at line 484 of file node.h.

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

Minimum Time Stamp Status for fix frequency diagnostic.

Definition at line 495 of file node.h.

ublox_msgs::CfgCFG ublox_node::UbloxNode::load_ [private]

Parameters to load from non-volatile memory during configuration.

Definition at line 638 of file node.h.

Max SBAS parameter (see CfgSBAS message)

Definition at line 634 of file node.h.

Determined From Mon VER.

Definition at line 594 of file node.h.

double ublox_node::UbloxNode::rate_ [private]

The measurement rate in Hz.

Definition at line 622 of file node.h.

raw data stream logging

Definition at line 645 of file node.h.

ublox_msgs::CfgCFG ublox_node::UbloxNode::save_ [private]

Parameters to save to non-volatile memory after configuration.

Definition at line 640 of file node.h.

SBAS Usage parameter (see CfgSBAS message)

Definition at line 632 of file node.h.

If true, set configure the User-Defined Datum.

Definition at line 624 of file node.h.

Whether to configure the USB port.

Set to true if usb_in & usb_out parameters are set

Definition at line 616 of file node.h.

rate for TIM-TM2

Definition at line 642 of file node.h.

uint16_t ublox_node::UbloxNode::uart_in_ [private]

UART in protocol (see CfgPRT message for constants)

Definition at line 609 of file node.h.

UART out protocol (see CfgPRT message for constants)

Definition at line 611 of file node.h.

uint16_t ublox_node::UbloxNode::usb_in_ [private]

USB in protocol (see CfgPRT message for constants)

Definition at line 618 of file node.h.

uint16_t ublox_node::UbloxNode::usb_out_ [private]

USB out protocol (see CfgPRT message for constants)

Definition at line 620 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 613 of file node.h.


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


ublox_gps
Author(s): Johannes Meyer
autogenerated on Fri Jun 14 2019 19:26:13