Implements functions for firmware version 6.
More...
#include <node.h>
Implements functions for firmware version 6.
Definition at line 697 of file node.h.
◆ UbloxFirmware6()
UbloxFirmware6::UbloxFirmware6 |
( |
| ) |
|
◆ 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
-
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
-
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
-
Definition at line 797 of file node.cpp.
◆ configureUblox()
bool UbloxFirmware6::configureUblox |
( |
| ) |
|
|
virtual |
◆ fixDiagnostic()
◆ getRosParams()
void UbloxFirmware6::getRosParams |
( |
| ) |
|
|
virtual |
◆ subscribe()
void UbloxFirmware6::subscribe |
( |
| ) |
|
|
virtual |
◆ 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: