Implements functions for High Precision GNSS Rover devices. More...
#include <node.h>
Public Member Functions | |
bool | configureUblox () |
Configure rover settings. | |
void | getRosParams () |
Get the ROS parameters specific to the Rover configuration. | |
void | initializeRosDiagnostics () |
Add diagnostic updaters for rover GNSS status, including status of RTCM messages. | |
void | subscribe () |
Subscribe to Rover messages, such as NavRELPOSNED. | |
Static Public Attributes | |
static constexpr double | kRtcmFreqMax = 10 |
Diagnostic updater: RTCM topic frequency max [Hz]. | |
static constexpr double | kRtcmFreqMin = 1 |
Diagnostic updater: RTCM topic frequency min [Hz]. | |
static constexpr double | kRtcmFreqTol = 0.1 |
Diagnostic updater: RTCM topic frequency tolerance [%]. | |
static constexpr int | kRtcmFreqWindow = 25 |
Diagnostic updater: RTCM topic frequency window [num messages]. | |
Protected Member Functions | |
void | callbackNavRelPosNed (const ublox_msgs::NavRELPOSNED &m) |
Set the last received message and call rover diagnostic updater. | |
void | carrierPhaseDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Update the rover diagnostics, including the carrier phase solution status (float or fixed). | |
Protected Attributes | |
uint8_t | dgnss_mode_ |
The DGNSS mode. | |
UbloxTopicDiagnostic | freq_rtcm_ |
The RTCM topic frequency diagnostic updater. | |
ublox_msgs::NavRELPOSNED | last_rel_pos_ |
Last relative position (used for diagnostic updater) |
void HpgRovProduct::callbackNavRelPosNed | ( | const ublox_msgs::NavRELPOSNED & | m | ) | [protected] |
void HpgRovProduct::carrierPhaseDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected] |
bool HpgRovProduct::configureUblox | ( | ) | [virtual] |
Configure rover settings.
Configure the DGNSS mode.
Implements ublox_node::ComponentInterface.
void HpgRovProduct::getRosParams | ( | ) | [virtual] |
Get the ROS parameters specific to the Rover configuration.
Get the DGNSS mode.
Implements ublox_node::ComponentInterface.
void HpgRovProduct::initializeRosDiagnostics | ( | ) | [virtual] |
Add diagnostic updaters for rover GNSS status, including status of RTCM messages.
Implements ublox_node::ComponentInterface.
void HpgRovProduct::subscribe | ( | ) | [virtual] |
Subscribe to Rover messages, such as NavRELPOSNED.
Implements ublox_node::ComponentInterface.
uint8_t ublox_node::HpgRovProduct::dgnss_mode_ [protected] |
constexpr double ublox_node::HpgRovProduct::kRtcmFreqMax = 10 [static] |
constexpr double ublox_node::HpgRovProduct::kRtcmFreqMin = 1 [static] |
constexpr double ublox_node::HpgRovProduct::kRtcmFreqTol = 0.1 [static] |
constexpr int ublox_node::HpgRovProduct::kRtcmFreqWindow = 25 [static] |
ublox_msgs::NavRELPOSNED ublox_node::HpgRovProduct::last_rel_pos_ [protected] |