Implements functions for firmware version 6. More...
#include <node.h>
Public Member Functions | |
bool | configureUblox () |
Prints a warning, GNSS configuration not available in this version. | |
void | getRosParams () |
Sets the fix status service type to GPS. | |
void | subscribe () |
Subscribe to NavPVT, RxmRAW, and RxmSFRB messages. | |
UbloxFirmware6 () | |
Protected Member Functions | |
void | fixDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages. | |
Private Member Functions | |
void | callbackNavPosLlh (const ublox_msgs::NavPOSLLH &m) |
Publish the fix and call the fix diagnostic updater. | |
void | callbackNavSol (const ublox_msgs::NavSOL &m) |
Update the number of SVs used for the fix. | |
void | callbackNavVelNed (const ublox_msgs::NavVELNED &m) |
Update the last known velocity. | |
Private Attributes | |
ublox_msgs::CfgNMEA6 | cfg_nmea_ |
Used to configure NMEA (if set_nmea_) filled with ROS parameters. | |
sensor_msgs::NavSatFix | fix_ |
The last NavSatFix based on last_nav_pos_. | |
ublox_msgs::NavPOSLLH | last_nav_pos_ |
The last received navigation position. | |
ublox_msgs::NavSOL | last_nav_sol_ |
The last received num SVs used. | |
ublox_msgs::NavVELNED | last_nav_vel_ |
The last received navigation velocity. | |
bool | set_nmea_ |
Whether or not to configure the NMEA settings. | |
geometry_msgs::TwistWithCovarianceStamped | velocity_ |
The last Twist based on last_nav_vel_. |
void UbloxFirmware6::callbackNavPosLlh | ( | const ublox_msgs::NavPOSLLH & | m | ) | [private] |
void UbloxFirmware6::callbackNavSol | ( | const ublox_msgs::NavSOL & | m | ) | [private] |
void UbloxFirmware6::callbackNavVelNed | ( | const ublox_msgs::NavVELNED & | m | ) | [private] |
bool UbloxFirmware6::configureUblox | ( | ) | [virtual] |
Prints a warning, GNSS configuration not available in this version.
Implements ublox_node::ComponentInterface.
void UbloxFirmware6::fixDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected, virtual] |
Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages.
Implements ublox_node::UbloxFirmware.
void UbloxFirmware6::getRosParams | ( | ) | [virtual] |
Sets the fix status service type to GPS.
Implements ublox_node::ComponentInterface.
void UbloxFirmware6::subscribe | ( | ) | [virtual] |
Subscribe to NavPVT, RxmRAW, and RxmSFRB messages.
Implements ublox_node::ComponentInterface.
ublox_msgs::CfgNMEA6 ublox_node::UbloxFirmware6::cfg_nmea_ [private] |
sensor_msgs::NavSatFix ublox_node::UbloxFirmware6::fix_ [private] |
ublox_msgs::NavPOSLLH ublox_node::UbloxFirmware6::last_nav_pos_ [private] |
ublox_msgs::NavSOL ublox_node::UbloxFirmware6::last_nav_sol_ [private] |
ublox_msgs::NavVELNED ublox_node::UbloxFirmware6::last_nav_vel_ [private] |
bool ublox_node::UbloxFirmware6::set_nmea_ [private] |
geometry_msgs::TwistWithCovarianceStamped ublox_node::UbloxFirmware6::velocity_ [private] |