Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
ublox_node::UbloxFirmware6 Class Reference

Implements functions for firmware version 6. More...

#include <node.h>

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

Public Member Functions

bool configureUblox ()
 Prints a warning, GNSS configuration not available in this version. More...
 
void getRosParams ()
 Sets the fix status service type to GPS. More...
 
void subscribe ()
 Subscribe to NavPVT, RxmRAW, and RxmSFRB messages. More...
 
 UbloxFirmware6 ()
 
- Public Member Functions inherited from ublox_node::UbloxFirmware
void initializeRosDiagnostics ()
 Add the fix diagnostics to the updater. More...
 

Protected Member Functions

void fixDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages. More...
 

Private Member Functions

void callbackNavPosLlh (const ublox_msgs::NavPOSLLH &m)
 Publish the fix and call the fix diagnostic updater. More...
 
void callbackNavSol (const ublox_msgs::NavSOL &m)
 Update the number of SVs used for the fix. More...
 
void callbackNavVelNed (const ublox_msgs::NavVELNED &m)
 Update the last known velocity. More...
 

Private Attributes

ublox_msgs::CfgNMEA6 cfg_nmea_
 Used to configure NMEA (if set_nmea_) filled with ROS parameters. More...
 
sensor_msgs::NavSatFix fix_
 The last NavSatFix based on last_nav_pos_. More...
 
ublox_msgs::NavPOSLLH last_nav_pos_
 The last received navigation position. More...
 
ublox_msgs::NavSOL last_nav_sol_
 The last received num SVs used. More...
 
ublox_msgs::NavVELNED last_nav_vel_
 The last received navigation velocity. More...
 
bool set_nmea_
 Whether or not to configure the NMEA settings. More...
 
geometry_msgs::TwistWithCovarianceStamped velocity_
 The last Twist based on last_nav_vel_. More...
 

Detailed Description

Implements functions for firmware version 6.

Definition at line 697 of file node.h.

Constructor & Destructor Documentation

◆ UbloxFirmware6()

UbloxFirmware6::UbloxFirmware6 ( )

Definition at line 628 of file node.cpp.

Member Function Documentation

◆ callbackNavPosLlh()

void UbloxFirmware6::callbackNavPosLlh ( const ublox_msgs::NavPOSLLH &  m)
private

Publish the fix and call the fix diagnostic updater.

Also updates the last known position and publishes the NavPosLLH message if publishing is enabled.

Parameters
mthe message to process

Definition at line 754 of file node.cpp.

◆ callbackNavSol()

void UbloxFirmware6::callbackNavSol ( const ublox_msgs::NavSOL &  m)
private

Update the number of SVs used for the fix.

Publish the message if publishing is enabled.

Parameters
mthe message to process

Definition at line 831 of file node.cpp.

◆ callbackNavVelNed()

void UbloxFirmware6::callbackNavVelNed ( const ublox_msgs::NavVELNED &  m)
private

Update the last known velocity.

Publish the message if publishing is enabled.

Parameters
mthe message to process

Definition at line 797 of file node.cpp.

◆ configureUblox()

bool UbloxFirmware6::configureUblox ( )
virtual

Prints a warning, GNSS configuration not available in this version.

Returns
true if configured correctly, false otherwise

Implements ublox_node::ComponentInterface.

Definition at line 672 of file node.cpp.

◆ fixDiagnostic()

void UbloxFirmware6::fixDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages.

Implements ublox_node::UbloxFirmware.

Definition at line 712 of file node.cpp.

◆ getRosParams()

void UbloxFirmware6::getRosParams ( )
virtual

Sets the fix status service type to GPS.

Implements ublox_node::ComponentInterface.

Definition at line 630 of file node.cpp.

◆ subscribe()

void UbloxFirmware6::subscribe ( )
virtual

Subscribe to NavPVT, RxmRAW, and RxmSFRB messages.

Implements ublox_node::ComponentInterface.

Definition at line 681 of file node.cpp.

Member Data Documentation

◆ cfg_nmea_

ublox_msgs::CfgNMEA6 ublox_node::UbloxFirmware6::cfg_nmea_
private

Used to configure NMEA (if set_nmea_) filled with ROS parameters.

Definition at line 762 of file node.h.

◆ fix_

sensor_msgs::NavSatFix ublox_node::UbloxFirmware6::fix_
private

The last NavSatFix based on last_nav_pos_.

Definition at line 757 of file node.h.

◆ last_nav_pos_

ublox_msgs::NavPOSLLH ublox_node::UbloxFirmware6::last_nav_pos_
private

The last received navigation position.

Definition at line 751 of file node.h.

◆ last_nav_sol_

ublox_msgs::NavSOL ublox_node::UbloxFirmware6::last_nav_sol_
private

The last received num SVs used.

Definition at line 755 of file node.h.

◆ last_nav_vel_

ublox_msgs::NavVELNED ublox_node::UbloxFirmware6::last_nav_vel_
private

The last received navigation velocity.

Definition at line 753 of file node.h.

◆ set_nmea_

bool ublox_node::UbloxFirmware6::set_nmea_
private

Whether or not to configure the NMEA settings.

Definition at line 764 of file node.h.

◆ velocity_

geometry_msgs::TwistWithCovarianceStamped ublox_node::UbloxFirmware6::velocity_
private

The last Twist based on last_nav_vel_.

Definition at line 759 of file node.h.


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


ublox_gps
Author(s): Johannes Meyer
autogenerated on Wed Dec 7 2022 03:47:53