This class represents u-blox ROS node for *all* firmware and product versions.
More...
Public Member Functions |
bool | configureUblox () |
| Configure the device based on ROS parameters.
|
void | getRosParams () |
| Get the node parameters from the ROS Parameter Server.
|
void | initializeRosDiagnostics () |
| Initialize the diagnostic updater and add the fix diagnostic.
|
void | printInf (const ublox_msgs::Inf &m, uint8_t id) |
| Print an INF message to the ROS console.
|
void | subscribe () |
| Subscribe to all requested u-blox messages.
|
| UbloxNode () |
| Initialize and run the u-blox node.
|
Static Public Attributes |
static constexpr float | kDiagnosticPeriod = 0.2 |
| [s] 5Hz diagnostic period
|
static constexpr double | kFixFreqTol = 0.15 |
| Tolerance for Fix topic frequency as percentage of target frequency.
|
static constexpr double | kFixFreqWindow = 10 |
| Window [num messages] for Fix Frequency Diagnostic.
|
static constexpr double | kPollDuration = 1.0 |
| how often (in seconds) to call poll messages
|
static constexpr int | kResetWait = 10 |
| How long to wait during I/O reset [s].
|
static constexpr double | kTimeStampStatusMin = 0 |
| Minimum Time Stamp Status for fix frequency diagnostic.
|
Private Member Functions |
void | addFirmwareInterface () |
| Add the interface for firmware specific configuration, subscribers, & diagnostics. This assumes the protocol_version_ has been set.
|
void | addProductInterface (std::string product_category, std::string ref_rov="") |
| Add the interface which is used for product category configuration, subscribers, & diagnostics.
|
void | configureInf () |
| Configure INF messages, call after subscribe.
|
void | initialize () |
| Initialize the U-Blox node. Configure the U-Blox and subscribe to messages.
|
void | initializeIo () |
| Initialize the I/O handling.
|
void | pollMessages (const ros::TimerEvent &event) |
| Poll messages from the U-Blox device.
|
void | processMonVer () |
| Process the MonVer message and add firmware and product components.
|
bool | resetDevice () |
| Send a reset message the u-blox device & re-initialize the I/O.
|
void | shutdown () |
| Shutdown the node. Closes the serial port.
|
Private Attributes |
uint32_t | baudrate_ |
| UART1 baudrate.
|
ublox_msgs::CfgDAT | cfg_dat_ |
| User-defined Datum.
|
std::vector< boost::shared_ptr
< ComponentInterface > > | components_ |
| The u-blox node components.
|
std::string | device_ |
| Device port.
|
uint8_t | dmodel_ |
| Set from dynamic model string.
|
uint8_t | dr_limit_ |
| Dead reckoning limit parameter.
|
std::string | dynamic_model_ |
| dynamic model type
|
bool | enable_ppp_ |
| Whether or not to enable PPP (advanced setting)
|
bool | enable_sbas_ |
| Whether or not to enable SBAS.
|
std::string | fix_mode_ |
| Fix mode type.
|
uint8_t | fmode_ |
| Set from fix mode string.
|
ublox_msgs::CfgCFG | load_ |
| Parameters to load from non-volatile memory during configuration.
|
uint8_t | max_sbas_ |
| Max SBAS parameter (see CfgSBAS message)
|
float | protocol_version_ = 0 |
| Determined From Mon VER.
|
double | rate_ |
| The measurement rate in Hz.
|
RawDataStreamPa | rawDataStreamPa_ |
| raw data stream logging
|
ublox_msgs::CfgCFG | save_ |
| Parameters to save to non-volatile memory after configuration.
|
uint8_t | sbas_usage_ |
| SBAS Usage parameter (see CfgSBAS message)
|
bool | set_dat_ |
| If true, set configure the User-Defined Datum.
|
bool | set_usb_ |
| Whether to configure the USB port.
|
uint8_t | tim_rate_ |
| rate for TIM-TM2
|
uint16_t | uart_in_ |
| UART in protocol (see CfgPRT message for constants)
|
uint16_t | uart_out_ |
| UART out protocol (see CfgPRT message for constants)
|
uint16_t | usb_in_ |
| USB in protocol (see CfgPRT message for constants)
|
uint16_t | usb_out_ |
| USB out protocol (see CfgPRT message for constants)
|
uint16_t | usb_tx_ |
| USB TX Ready Pin configuration (see CfgPRT message for constants)
|
This class represents u-blox ROS node for *all* firmware and product versions.
It loads the user parameters, configures the u-blox device, subscribes to u-blox messages, and configures the device hardware. Functionality specific to a given product or firmware version, etc. should NOT be implemented in this class. Instead, the user should add the functionality to the appropriate implementation of ComponentInterface. If necessary, the user should create a class which implements u-blox interface, then add a pointer to an instance of the class to the components vector. The UbloxNode calls the public methods of ComponentInterface for each element in the components vector.
Definition at line 481 of file node.h.