Classes | Namespaces | Typedefs | Functions | Variables
node.h File Reference
#include <vector>
#include <set>
#include <boost/algorithm/string.hpp>
#include <boost/lexical_cast.hpp>
#include <boost/regex.hpp>
#include <ros/ros.h>
#include <ros/console.h>
#include <ros/serialization.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>
#include <geometry_msgs/TwistWithCovarianceStamped.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/TimeReference.h>
#include <sensor_msgs/Imu.h>
#include <ublox_msgs/ublox_msgs.h>
#include <ublox_gps/gps.h>
#include <ublox_gps/utils.h>
#include <ublox_gps/raw_data_pa.h>
Include dependency graph for node.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  ublox_node::AdrUdrProduct
 Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices. More...
class  ublox_node::ComponentInterface
 This interface is used to add functionality to the main node. More...
struct  ublox_node::FixDiagnostic
 Topic diagnostics for fix / fix_velocity messages. More...
class  ublox_node::FtsProduct
 Implements functions for FTS products. Currently unimplemented. More...
class  ublox_node::HpgRefProduct
 Implements functions for High Precision GNSS Reference station devices. More...
class  ublox_node::HpgRovProduct
 Implements functions for High Precision GNSS Rover devices. More...
class  ublox_node::RawDataProduct
 Implements functions for Raw Data products. More...
class  ublox_node::TimProduct
 Implements functions for Time Sync products. More...
class  ublox_node::UbloxFirmware
 This abstract class represents a firmware component. More...
class  ublox_node::UbloxFirmware6
 Implements functions for firmware version 6. More...
class  ublox_node::UbloxFirmware7
 Implements functions for firmware version 7. More...
class  ublox_node::UbloxFirmware7Plus< NavPVT >
class  ublox_node::UbloxFirmware8
 Implements functions for firmware version 8. More...
class  ublox_node::UbloxNode
 This class represents u-blox ROS node for *all* firmware and product versions. More...
struct  ublox_node::UbloxTopicDiagnostic
 Topic diagnostics for u-blox messages. More...

Namespaces

namespace  ublox_node

Typedefs

typedef boost::shared_ptr
< ComponentInterface > 
ublox_node::ComponentPtr

Functions

template<typename V , typename T >
void ublox_node::checkMin (V val, T min, std::string name)
 Check that the parameter is above the minimum.
template<typename V , typename T >
void ublox_node::checkRange (V val, T min, T max, std::string name)
 Check that the parameter is in the range.
template<typename V , typename T >
void ublox_node::checkRange (std::vector< V > val, T min, T max, std::string name)
 Check that the elements of the vector are in the range.
uint8_t ublox_node::fixModeFromString (const std::string &mode)
 Determine fix mode from human-readable string.
template<typename I >
bool ublox_node::getRosInt (const std::string &key, I &u)
 Get a integer (size 8 or 16) value from the parameter server.
template<typename U , typename V >
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.
template<typename I >
bool ublox_node::getRosInt (const std::string &key, std::vector< I > &i)
 Get a int (size 8 or 16) vector from the parameter server.
template<typename U >
bool ublox_node::getRosUint (const std::string &key, U &u)
 Get a unsigned integer value from the parameter server.
template<typename U , typename V >
void ublox_node::getRosUint (const std::string &key, U &u, V default_val)
 Get a unsigned integer value from the parameter server.
template<typename U >
bool ublox_node::getRosUint (const std::string &key, std::vector< U > &u)
 Get a unsigned integer vector from the parameter server.
uint8_t ublox_node::modelFromString (const std::string &model)
 Determine dynamic model from human-readable string.
template<typename MessageT >
void ublox_node::publish (const MessageT &m, const std::string &topic)
 Publish a ROS message of type MessageT.
bool ublox_node::supportsGnss (std::string gnss)

Variables

bool ublox_node::config_on_startup_flag_
 Flag for enabling configuration on startup.
std::map< std::string, bool > ublox_node::enabled
 Whether or not to publish the given ublox message.
int ublox_node::fix_status_service
std::string ublox_node::frame_id
 The ROS frame ID of this device.
FixDiagnostic ublox_node::freq_diag
 fix frequency diagnostic updater
ublox_gps::Gps ublox_node::gps
 Handles communication with the U-Blox Device.
static constexpr uint16_t ublox_node::kDefaultMeasPeriod = 250
 Default measurement period for HPG devices.
static constexpr uint32_t ublox_node::kNavSvInfoSubscribeRate = 20
 Subscribe Rate for u-blox SV Info messages.
static constexpr uint32_t ublox_node::kROSQueueSize = 1
 Queue size for ROS publishers.
static constexpr uint32_t ublox_node::kSubscribeRate = 1
 Default subscribe Rate to u-blox messages [Hz].
uint16_t ublox_node::meas_rate
 The measurement [ms], see CfgRate.msg.
uint16_t ublox_node::nav_rate
 Navigation rate in measurement cycles, see CfgRate.msg.
boost::shared_ptr
< ros::NodeHandle
ublox_node::nh
 Node Handle for GPS node.
std::vector< uint8_t > ublox_node::rtcm_ids
 IDs of RTCM out messages to configure.
std::vector< uint8_t > ublox_node::rtcm_rates
 Rates of RTCM out messages. Size must be the same as rtcm_ids.
std::set< std::string > ublox_node::supported
 Which GNSS are supported by the device.
boost::shared_ptr
< diagnostic_updater::Updater
ublox_node::updater
 ROS diagnostic updater.


ublox_gps
Author(s): Johannes Meyer
autogenerated on Fri Jun 14 2019 19:26:13