Public Types | Public Member Functions | Public Attributes | Private Types | Private Attributes | Static Private Attributes | List of all members
io_comm_rx::CallbackHandlers Class Reference

Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class. More...

#include <callback_handlers.hpp>

Public Types

typedef std::multimap< std::string, boost::shared_ptr< AbstractCallbackHandler > > CallbackMap
 

Public Member Functions

 CallbackHandlers (ROSaicNodeBase *node, Settings *settings)
 
void handle ()
 Called every time rx_message is found to contain some potentially useful message. More...
 
template<typename T >
CallbackMap insert (std::string message_key)
 Adds a pair to the multimap "callbackmap_", with the message_key being the key. More...
 
void readCallback (Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
 Searches for Rx messages that could potentially be decoded/parsed/published. More...
 

Public Attributes

CallbackMap callbackmap_
 

Private Types

typedef std::unordered_map< std::string, uint32_t > DiagnosticArrayMap
 
typedef std::unordered_map< std::string, uint32_t > GPSFixMap
 
typedef std::unordered_map< std::string, uint32_t > ImuMap
 
typedef std::unordered_map< std::string, uint32_t > LocalizationMap
 
typedef std::unordered_map< std::string, uint32_t > NavSatFixMap
 
typedef std::unordered_map< std::string, uint32_t > PoseWithCovarianceStampedMap
 

Private Attributes

ROSaicNodeBasenode_
 Pointer to Node. More...
 
RxMessage rx_message_
 RxMessage parser. More...
 
Settingssettings_
 Settings. More...
 

Static Private Attributes

static boost::mutex callback_mutex_
 
static DiagnosticArrayMap diagnosticarray_map
 
static std::string do_diagnostics_ = "4014"
 
static std::string do_gpsfix_ = "4007"
 
static std::string do_imu_ = "4226"
 
static std::string do_insgpsfix_ = "4226"
 
static std::string do_inslocalization_ = "4226"
 
static std::string do_insnavsatfix_ = "4226"
 
static std::string do_inspose_ = "4226"
 
static std::string do_navsatfix_ = "4007"
 
static std::string do_pose_ = "4007"
 
static GPSFixMap gpsfix_map
 
static ImuMap imu_map
 
static LocalizationMap localization_map
 
static NavSatFixMap navsatfix_map
 
static PoseWithCovarianceStampedMap pose_map
 

Detailed Description

Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class.

Definition at line 181 of file callback_handlers.hpp.

Member Typedef Documentation

◆ CallbackMap

Key is std::string and represents the ROS message key, value is boost::shared_ptr<CallbackHandler>

Definition at line 189 of file callback_handlers.hpp.

◆ DiagnosticArrayMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::DiagnosticArrayMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for DiagnosticArray to a uint32_t

Definition at line 328 of file callback_handlers.hpp.

◆ GPSFixMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::GPSFixMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for GPSFix to a uint32_t

Definition at line 304 of file callback_handlers.hpp.

◆ ImuMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::ImuMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for Imu to a uint32_t

Definition at line 336 of file callback_handlers.hpp.

◆ LocalizationMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::LocalizationMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for Localization to a uint32_t

Definition at line 344 of file callback_handlers.hpp.

◆ NavSatFixMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::NavSatFixMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for NavSatFix to a uint32_t

Definition at line 312 of file callback_handlers.hpp.

◆ PoseWithCovarianceStampedMap

typedef std::unordered_map<std::string, uint32_t> io_comm_rx::CallbackHandlers::PoseWithCovarianceStampedMap
private

Shorthand for the map responsible for matching ROS message identifiers relevant for PoseWithCovarianceStamped to a uint32_t

Definition at line 320 of file callback_handlers.hpp.

Constructor & Destructor Documentation

◆ CallbackHandlers()

io_comm_rx::CallbackHandlers::CallbackHandlers ( ROSaicNodeBase node,
Settings settings 
)
inline

Definition at line 191 of file callback_handlers.hpp.

Member Function Documentation

◆ handle()

void io_comm_rx::CallbackHandlers::handle ( )

Called every time rx_message is found to contain some potentially useful message.

The for loop forwards to a ROS message specific handle if the latter was added via callbackmap_.insert at some earlier point.

Definition at line 90 of file callback_handlers.cpp.

◆ insert()

template<typename T >
CallbackMap io_comm_rx::CallbackHandlers::insert ( std::string  message_key)
inline

Adds a pair to the multimap "callbackmap_", with the message_key being the key.

This method is called by "handlers_" in rosaic_node.cpp. T would be a (custom or not) ROS message, e.g. PVTGeodeticMsg, or nmea_msgs::GPGGA. Note that "typename" could be omitted in the argument.

Parameters
message_keyThe pair's key
Returns
The modified multimap "callbackmap_"

Definition at line 209 of file callback_handlers.hpp.

◆ readCallback()

void io_comm_rx::CallbackHandlers::readCallback ( Timestamp  recvTimestamp,
const uint8_t *  data,
std::size_t &  size 
)

Searches for Rx messages that could potentially be decoded/parsed/published.

Parameters
[in]recvTimestampTimestamp of buffer reception passed on from AsyncManager class
[in]dataBuffer passed on from AsyncManager class
[in]sizeSize of the buffer

Definition at line 468 of file callback_handlers.cpp.

Member Data Documentation

◆ callback_mutex_

boost::mutex io_comm_rx::CallbackHandlers::callback_mutex_
staticprivate

The "static" keyword resolves construct-by-copying issues related to this mutex by making it available throughout the code unit. The mutex constructor list contains "mutex (const mutex&) = delete", hence construct-by-copying a mutex is explicitly prohibited. The get_handlers() method of the Comm_IO class hence forces us to make this mutex static.

Definition at line 258 of file callback_handlers.hpp.

◆ callbackmap_

CallbackMap io_comm_rx::CallbackHandlers::callbackmap_

Callback handlers multimap for Rx messages; it needs to be public since we copy-assign (did not work otherwise) new callbackmap_, after inserting a pair to the multimap within the DefineMessages() method of the ROSaicNode class, onto its old version.

Definition at line 241 of file callback_handlers.hpp.

◆ diagnosticarray_map

CallbackHandlers::DiagnosticArrayMap io_comm_rx::CallbackHandlers::diagnosticarray_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 332 of file callback_handlers.hpp.

◆ do_diagnostics_

std::string io_comm_rx::CallbackHandlers::do_diagnostics_ = "4014"
staticprivate

Determines which of the SBF blocks necessary for the diagnostic_msgs/DiagnosticArray ROS message arrives last and thus launches its construction

Definition at line 290 of file callback_handlers.hpp.

◆ do_gpsfix_

std::string io_comm_rx::CallbackHandlers::do_gpsfix_ = "4007"
staticprivate

Determines which of the SBF blocks necessary for the gps_common::GPSFix ROS message arrives last and thus launches its construction

Definition at line 262 of file callback_handlers.hpp.

◆ do_imu_

std::string io_comm_rx::CallbackHandlers::do_imu_ = "4226"
staticprivate

Determines which of the SBF blocks necessary for the sensor_msgs/Imu ROS message arrives last and thus launches its construction

Definition at line 295 of file callback_handlers.hpp.

◆ do_insgpsfix_

std::string io_comm_rx::CallbackHandlers::do_insgpsfix_ = "4226"
staticprivate

Determines which of the INS integrated SBF blocks necessary for the gps_common::GPSFix ROS message arrives last and thus launches its construction

Definition at line 266 of file callback_handlers.hpp.

◆ do_inslocalization_

std::string io_comm_rx::CallbackHandlers::do_inslocalization_ = "4226"
staticprivate

Determines which of the SBF blocks necessary for the nav_msgs/Odometry ROS message arrives last and thus launches its construction

Definition at line 300 of file callback_handlers.hpp.

◆ do_insnavsatfix_

std::string io_comm_rx::CallbackHandlers::do_insnavsatfix_ = "4226"
staticprivate

Determines which of the INS integrated SBF blocks necessary for the NavSatFixMsg ROS message arrives last and thus launches its construction

Definition at line 275 of file callback_handlers.hpp.

◆ do_inspose_

std::string io_comm_rx::CallbackHandlers::do_inspose_ = "4226"
staticprivate

Determines which of the INS integrated SBF blocks necessary for the geometry_msgs/PoseWithCovarianceStamped ROS message arrives last and thus launches its construction

Definition at line 285 of file callback_handlers.hpp.

◆ do_navsatfix_

std::string io_comm_rx::CallbackHandlers::do_navsatfix_ = "4007"
staticprivate

Determines which of the SBF blocks necessary for the NavSatFixMsg ROS message arrives last and thus launches its construction

Definition at line 271 of file callback_handlers.hpp.

◆ do_pose_

std::string io_comm_rx::CallbackHandlers::do_pose_ = "4007"
staticprivate

Determines which of the SBF blocks necessary for the geometry_msgs/PoseWithCovarianceStamped ROS message arrives last and thus launches its construction

Definition at line 280 of file callback_handlers.hpp.

◆ gpsfix_map

CallbackHandlers::GPSFixMap io_comm_rx::CallbackHandlers::gpsfix_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 308 of file callback_handlers.hpp.

◆ imu_map

CallbackHandlers::ImuMap io_comm_rx::CallbackHandlers::imu_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 340 of file callback_handlers.hpp.

◆ localization_map

CallbackHandlers::LocalizationMap io_comm_rx::CallbackHandlers::localization_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 348 of file callback_handlers.hpp.

◆ navsatfix_map

CallbackHandlers::NavSatFixMap io_comm_rx::CallbackHandlers::navsatfix_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 316 of file callback_handlers.hpp.

◆ node_

ROSaicNodeBase* io_comm_rx::CallbackHandlers::node_
private

Pointer to Node.

Definition at line 245 of file callback_handlers.hpp.

◆ pose_map

CallbackHandlers::PoseWithCovarianceStampedMap io_comm_rx::CallbackHandlers::pose_map
staticprivate

All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static

Definition at line 324 of file callback_handlers.hpp.

◆ rx_message_

RxMessage io_comm_rx::CallbackHandlers::rx_message_
private

RxMessage parser.

Definition at line 248 of file callback_handlers.hpp.

◆ settings_

Settings* io_comm_rx::CallbackHandlers::settings_
private

Settings.

Definition at line 251 of file callback_handlers.hpp.


The documentation for this class was generated from the following files:


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56