Classes | |
| class | AdrUdrProduct |
| Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices. More... | |
| class | ComponentInterface |
| This interface is used to add functionality to the main node. More... | |
| struct | FixDiagnostic |
| Topic diagnostics for fix / fix_velocity messages. More... | |
| class | FtsProduct |
| Implements functions for FTS products. Currently unimplemented. More... | |
| class | HpgRefProduct |
| Implements functions for High Precision GNSS Reference station devices. More... | |
| class | HpgRovProduct |
| Implements functions for High Precision GNSS Rover devices. More... | |
| class | HpPosRecProduct |
| class | RawDataProduct |
| Implements functions for Raw Data products. More... | |
| class | RawDataStreamPa |
| Implements functions for raw data stream. More... | |
| class | TimProduct |
| Implements functions for Time Sync products. More... | |
| class | UbloxFirmware |
| This abstract class represents a firmware component. More... | |
| class | UbloxFirmware6 |
| Implements functions for firmware version 6. More... | |
| class | UbloxFirmware7 |
| Implements functions for firmware version 7. More... | |
| class | UbloxFirmware7Plus |
| class | UbloxFirmware8 |
| Implements functions for firmware version 8. More... | |
| class | UbloxFirmware9 |
| Implements functions for firmware version 9. For now it simply re-uses the firmware version 8 class but allows for future expansion of functionality. More... | |
| class | UbloxNode |
| This class represents u-blox ROS node for all firmware and product versions. More... | |
| struct | UbloxTopicDiagnostic |
| Topic diagnostics for u-blox messages. More... | |
Typedefs | |
| typedef boost::shared_ptr< ComponentInterface > | ComponentPtr |
Functions | |
| template<typename V , typename T > | |
| void | checkMin (V val, T min, std::string name) |
| Check that the parameter is above the minimum. More... | |
| template<typename V , typename T > | |
| void | checkRange (V val, T min, T max, std::string name) |
| Check that the parameter is in the range. More... | |
| template<typename V , typename T > | |
| void | checkRange (std::vector< V > val, T min, T max, std::string name) |
| Check that the elements of the vector are in the range. More... | |
| uint8_t | fixModeFromString (const std::string &mode) |
| Determine fix mode from human-readable string. More... | |
| template<typename I > | |
| bool | getRosInt (const std::string &key, I &u) |
| Get a integer (size 8 or 16) value from the parameter server. More... | |
| template<typename U , typename V > | |
| void | getRosInt (const std::string &key, U &u, V default_val) |
| Get an integer value (size 8 or 16) from the parameter server. More... | |
| template<typename I > | |
| bool | getRosInt (const std::string &key, std::vector< I > &i) |
| Get a int (size 8 or 16) vector from the parameter server. More... | |
| template<typename U > | |
| bool | getRosUint (const std::string &key, U &u) |
| Get a unsigned integer value from the parameter server. More... | |
| template<typename U , typename V > | |
| void | getRosUint (const std::string &key, U &u, V default_val) |
| Get a unsigned integer value from the parameter server. More... | |
| template<typename U > | |
| bool | getRosUint (const std::string &key, std::vector< U > &u) |
| Get a unsigned integer vector from the parameter server. More... | |
| uint8_t | modelFromString (const std::string &model) |
| Determine dynamic model from human-readable string. More... | |
| template<typename MessageT > | |
| void | publish (const MessageT &m, const std::string &topic) |
| Publish a ROS message of type MessageT. More... | |
| void | publish_nmea (const std::string &sentence, const std::string &topic) |
| bool | supportsGnss (std::string gnss) |
Variables | |
| bool | config_on_startup_flag_ |
| Flag for enabling configuration on startup. More... | |
| std::map< std::string, bool > | enabled |
| Whether or not to publish the given ublox message. More... | |
| int | fix_status_service |
| std::string | frame_id |
| The ROS frame ID of this device. More... | |
| boost::shared_ptr< FixDiagnostic > | freq_diag |
| fix frequency diagnostic updater More... | |
| ublox_gps::Gps | gps |
| Handles communication with the U-Blox Device. More... | |
| static constexpr uint16_t | kDefaultMeasPeriod = 250 |
| Default measurement period for HPG devices. More... | |
| static constexpr uint32_t | kNavSvInfoSubscribeRate = 20 |
| Subscribe Rate for u-blox SV Info messages. More... | |
| static constexpr uint32_t | kROSQueueSize = 1 |
| Queue size for ROS publishers. More... | |
| static constexpr uint32_t | kSubscribeRate = 1 |
| Default subscribe Rate to u-blox messages [Hz]. More... | |
| uint16_t | meas_rate |
| The measurement [ms], see CfgRate.msg. More... | |
| uint16_t | nav_rate |
| Navigation rate in measurement cycles, see CfgRate.msg. More... | |
| boost::shared_ptr< ros::NodeHandle > | nh |
| Node Handle for GPS node. More... | |
| std::vector< uint8_t > | rtcm_ids |
| IDs of RTCM out messages to configure. More... | |
| std::vector< uint8_t > | rtcm_rates |
| Rates of RTCM out messages. Size must be the same as rtcm_ids. More... | |
| std::set< std::string > | supported |
| Which GNSS are supported by the device. More... | |
| boost::shared_ptr< diagnostic_updater::Updater > | updater |
| ROS diagnostic updater. More... | |
This namespace is for the ROS u-blox node and handles anything regarding ROS parameters, message passing, diagnostics, etc.
| void ublox_node::checkMin | ( | V | val, |
| T | min, | ||
| std::string | name | ||
| ) |
| void ublox_node::checkRange | ( | V | val, |
| T | min, | ||
| T | max, | ||
| std::string | name | ||
| ) |
| void ublox_node::checkRange | ( | std::vector< V > | val, |
| T | min, | ||
| T | max, | ||
| std::string | name | ||
| ) |
| uint8_t ublox_node::fixModeFromString | ( | const std::string & | mode | ) |
| bool ublox_node::getRosInt | ( | const std::string & | key, |
| I & | u | ||
| ) |
Get a integer (size 8 or 16) value from the parameter server.
| key | the key to be used in the parameter server's dictionary |
| u | storage for the retrieved value. |
| std::runtime_error | if the parameter is out of bounds |
| void ublox_node::getRosInt | ( | const std::string & | key, |
| U & | u, | ||
| V | default_val | ||
| ) |
Get an integer value (size 8 or 16) from the parameter server.
| key | the key to be used in the parameter server's dictionary |
| u | storage for the retrieved value. |
| val | value to use if the server doesn't contain this parameter. |
| std::runtime_error | if the parameter is out of bounds |
| bool ublox_node::getRosInt | ( | const std::string & | key, |
| std::vector< I > & | i | ||
| ) |
| bool ublox_node::getRosUint | ( | const std::string & | key, |
| U & | u | ||
| ) |
Get a unsigned integer value from the parameter server.
| key | the key to be used in the parameter server's dictionary |
| u | storage for the retrieved value. |
| std::runtime_error | if the parameter is out of bounds |
| void ublox_node::getRosUint | ( | const std::string & | key, |
| U & | u, | ||
| V | default_val | ||
| ) |
Get a unsigned integer value from the parameter server.
| key | the key to be used in the parameter server's dictionary |
| u | storage for the retrieved value. |
| val | value to use if the server doesn't contain this parameter. |
| std::runtime_error | if the parameter is out of bounds |
| bool ublox_node::getRosUint | ( | const std::string & | key, |
| std::vector< U > & | u | ||
| ) |
| uint8_t ublox_node::modelFromString | ( | const std::string & | model | ) |
Determine dynamic model from human-readable string.
| model | One of the following (case-insensitive):
|
| std::runtime_error | on invalid argument. |
| void ublox_node::publish | ( | const MessageT & | m, |
| const std::string & | topic | ||
| ) |
| void ublox_node::publish_nmea | ( | const std::string & | sentence, |
| const std::string & | topic | ||
| ) |
| bool ublox_node::supportsGnss | ( | std::string | gnss | ) |
| bool ublox_node::config_on_startup_flag_ |
| std::map<std::string, bool> ublox_node::enabled |
| int ublox_node::fix_status_service |
| std::string ublox_node::frame_id |
| boost::shared_ptr<FixDiagnostic> ublox_node::freq_diag |
| ublox_gps::Gps ublox_node::gps |
|
static |
|
static |
|
static |
|
static |
| uint16_t ublox_node::meas_rate |
| uint16_t ublox_node::nav_rate |
| boost::shared_ptr<ros::NodeHandle> ublox_node::nh |
| std::vector<uint8_t> ublox_node::rtcm_ids |
| std::vector<uint8_t> ublox_node::rtcm_rates |
| std::set<std::string> ublox_node::supported |
| boost::shared_ptr<diagnostic_updater::Updater> ublox_node::updater |