#include <node.h>

Public Member Functions | |
| void | subscribe () |
| Subscribe to Rover messages, such as NavRELPOSNED. More... | |
Public Member Functions inherited from ublox_node::HpgRefProduct | |
| void | callbackNavSvIn (ublox_msgs::NavSVIN m) |
| Update the last received NavSVIN message and call diagnostic updater. More... | |
| bool | configureUblox () |
| Configure the u-blox Reference Station settings. More... | |
| void | getRosParams () |
| Get the ROS parameters specific to the Reference Station configuration. More... | |
| void | initializeRosDiagnostics () |
| Add diagnostic updaters for the TMODE3 status. More... | |
Protected Member Functions | |
| void | callbackNavHpPosLlh (const ublox_msgs::NavHPPOSLLH &m) |
| Publish a sensor_msgs/NavSatFix message upon receiving a HPPOSLLH UBX message. More... | |
| void | callbackNavRelPosNed (const ublox_msgs::NavRELPOSNED9 &m) |
| Set the last received message and call rover diagnostic updater. More... | |
Protected Member Functions inherited from ublox_node::HpgRefProduct | |
| bool | setTimeMode () |
| Set the device mode to time mode (internal state variable). More... | |
| void | tmode3Diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| Update the TMODE3 diagnostics. More... | |
Protected Attributes | |
| sensor_msgs::Imu | imu_ |
| ublox_msgs::NavRELPOSNED9 | last_rel_pos_ |
| Last relative position (used for diagnostic updater) More... | |
Protected Attributes inherited from ublox_node::HpgRefProduct | |
| std::vector< float > | arp_position_ |
| Antenna Reference Point Position [m] or [deg]. More... | |
| std::vector< int8_t > | arp_position_hp_ |
| Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9]. More... | |
| float | fixed_pos_acc_ |
| Fixed Position Accuracy [m]. More... | |
| ublox_msgs::NavSVIN | last_nav_svin_ |
| The last received Nav SVIN message. More... | |
| bool | lla_flag_ |
| True if coordinates are in LLA, false if ECEF. More... | |
| enum ublox_node::HpgRefProduct:: { ... } | mode_ |
| Status of device time mode. More... | |
| float | sv_in_acc_lim_ |
| Survey in accuracy limit [m]. More... | |
| uint32_t | sv_in_min_dur_ |
| Measurement period used during Survey-In [s]. More... | |
| bool | svin_reset_ |
| Whether to always reset the survey-in during configuration. More... | |
| uint8_t | tmode3_ |
| TMODE3 to set, such as disabled, survey-in, fixed. More... | |
Additional Inherited Members | |
Protected Types inherited from ublox_node::HpgRefProduct | |
| enum | { INIT, FIXED, DISABLED, SURVEY_IN, TIME } |
| Status of device time mode. More... | |
|
protected |
|
protected |
|
virtual |
Subscribe to Rover messages, such as NavRELPOSNED.
Reimplemented from ublox_node::HpgRefProduct.
|
protected |
|
protected |