Classes | Typedefs | Functions | Variables
ublox_node Namespace Reference

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

Variables

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

Detailed Description

This namespace is for the ROS u-blox node and handles anything regarding ROS parameters, message passing, diagnostics, etc.


Typedef Documentation

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

Definition at line 464 of file node.h.


Function Documentation

template<typename V , typename T >
void ublox_node::checkMin ( val,
T  min,
std::string  name 
)

Check that the parameter is above the minimum.

Parameters:
valthe value to check
minthe minimum for this value
namethe name of the parameter
Exceptions:
std::runtime_errorif it is below the minimum

Definition at line 255 of file node.h.

template<typename V , typename T >
void ublox_node::checkRange ( val,
T  min,
T  max,
std::string  name 
)

Check that the parameter is in the range.

Parameters:
valthe value to check
minthe minimum for this value
maxthe maximum for this value
namethe name of the parameter
Exceptions:
std::runtime_errorif it is out of bounds

Definition at line 272 of file node.h.

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.

Parameters:
valthe vector to check
minthe minimum for this value
maxthe maximum for this value
namethe name of the parameter
Exceptions:
std::runtime_errorvalue it is out of bounds

Definition at line 290 of file node.h.

uint8_t ublox_node::fixModeFromString ( const std::string &  mode)

Determine fix mode from human-readable string.

Parameters:
modeOne of the following (case-insensitive):
  • 2d
  • 3d
  • auto
Returns:
FixMode
Exceptions:
std::runtime_erroron invalid argument.

Definition at line 67 of file node.cpp.

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.

Parameters:
keythe key to be used in the parameter server's dictionary
ustorage for the retrieved value.
Exceptions:
std::runtime_errorif the parameter is out of bounds
Returns:
true if found, false if not found.

Definition at line 360 of file node.h.

template<typename U , typename V >
void ublox_node::getRosInt ( const std::string &  key,
U &  u,
default_val 
)

Get an integer value (size 8 or 16) from the parameter server.

Parameters:
keythe key to be used in the parameter server's dictionary
ustorage for the retrieved value.
valvalue to use if the server doesn't contain this parameter.
Exceptions:
std::runtime_errorif the parameter is out of bounds
Returns:
true if found, false if not found.

Definition at line 381 of file node.h.

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.

Exceptions:
std::runtime_errorif the parameter is out of bounds.
Returns:
true if found, false if not found.

Definition at line 392 of file node.h.

template<typename U >
bool ublox_node::getRosUint ( const std::string &  key,
U &  u 
)

Get a unsigned integer value from the parameter server.

Parameters:
keythe key to be used in the parameter server's dictionary
ustorage for the retrieved value.
Exceptions:
std::runtime_errorif the parameter is out of bounds
Returns:
true if found, false if not found.

Definition at line 306 of file node.h.

template<typename U , typename V >
void ublox_node::getRosUint ( const std::string &  key,
U &  u,
default_val 
)

Get a unsigned integer value from the parameter server.

Parameters:
keythe key to be used in the parameter server's dictionary
ustorage for the retrieved value.
valvalue to use if the server doesn't contain this parameter.
Exceptions:
std::runtime_errorif the parameter is out of bounds
Returns:
true if found, false if not found.

Definition at line 327 of file node.h.

template<typename U >
bool ublox_node::getRosUint ( const std::string &  key,
std::vector< U > &  u 
)

Get a unsigned integer vector from the parameter server.

Exceptions:
std::runtime_errorif the parameter is out of bounds.
Returns:
true if found, false if not found.

Definition at line 338 of file node.h.

uint8_t ublox_node::modelFromString ( const std::string &  model)

Determine dynamic model from human-readable string.

Parameters:
modelOne of the following (case-insensitive):
  • portable
  • stationary
  • pedestrian
  • automotive
  • sea
  • airborne1
  • airborne2
  • airborne4
  • wristwatch
Returns:
DynamicModel
Exceptions:
std::runtime_erroron invalid argument.

Definition at line 40 of file node.cpp.

template<typename MessageT >
void ublox_node::publish ( const MessageT &  m,
const std::string &  topic 
)

Publish a ROS message of type MessageT.

This function should be used to publish all messages which are simply read from u-blox and published.

Parameters:
mthe message to publish
topicthe topic to publish the message on

Definition at line 415 of file node.h.

bool ublox_node::supportsGnss ( std::string  gnss)
Parameters:
gnssThe string representing the GNSS. Refer MonVER message protocol. i.e. GPS, GLO, GAL, BDS, QZSS, SBAS, IMES
Returns:
true if the device supports the given GNSS

Definition at line 426 of file node.h.


Variable Documentation

Flag for enabling configuration on startup.

Definition at line 125 of file node.h.

std::map<std::string, bool> ublox_node::enabled

Whether or not to publish the given ublox message.

key is the message name (all lowercase) without firmware version numbers (e.g. NavPVT instead of NavPVT7). Value indicates whether or not to enable the message.

Definition at line 110 of file node.h.

The fix status service type, set in the Firmware Component based on the enabled GNSS

Definition at line 115 of file node.h.

std::string ublox_node::frame_id

The ROS frame ID of this device.

Definition at line 112 of file node.h.

fix frequency diagnostic updater

Definition at line 217 of file node.h.

Handles communication with the U-Blox Device.

Definition at line 102 of file node.h.

constexpr uint16_t ublox_node::kDefaultMeasPeriod = 250 [static]

Default measurement period for HPG devices.

Definition at line 89 of file node.h.

constexpr uint32_t ublox_node::kNavSvInfoSubscribeRate = 20 [static]

Subscribe Rate for u-blox SV Info messages.

Definition at line 93 of file node.h.

constexpr uint32_t ublox_node::kROSQueueSize = 1 [static]

Queue size for ROS publishers.

Definition at line 87 of file node.h.

constexpr uint32_t ublox_node::kSubscribeRate = 1 [static]

Default subscribe Rate to u-blox messages [Hz].

Definition at line 91 of file node.h.

The measurement [ms], see CfgRate.msg.

Definition at line 117 of file node.h.

Navigation rate in measurement cycles, see CfgRate.msg.

Definition at line 119 of file node.h.

boost::shared_ptr<ros::NodeHandle> ublox_node::nh

Node Handle for GPS node.

Definition at line 99 of file node.h.

std::vector<uint8_t> ublox_node::rtcm_ids

IDs of RTCM out messages to configure.

Definition at line 121 of file node.h.

std::vector<uint8_t> ublox_node::rtcm_rates

Rates of RTCM out messages. Size must be the same as rtcm_ids.

Definition at line 123 of file node.h.

Which GNSS are supported by the device.

Definition at line 104 of file node.h.

ROS diagnostic updater.

Definition at line 97 of file node.h.



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