ROSaic
|
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 |
Key is std::string and represents the ROS message key, value is boost::shared_ptr<CallbackHandler> More... | |
Public Member Functions | |
CallbackHandlers ()=default | |
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 | handle (RxMessage &rx_message) |
Ćalled every time rx_message is found to contain some potentially useful message. More... | |
void | readCallback (const uint8_t *data, std::size_t &size) |
Searches for Rx messages that could potentially be decoded/parsed/published. More... | |
Data Fields | |
CallbackMap | callbackmap_ |
Private Types | |
typedef std::map< std::string, uint32_t > | GPSFixMap |
Shorthand for the map responsible for matching ROS message identifiers relevant for GPSFix to a uint32_t. More... | |
typedef std::map< std::string, uint32_t > | NavSatFixMap |
Shorthand for the map responsible for matching ROS message identifiers relevant for NavSatFix to a uint32_t. More... | |
typedef std::map< std::string, uint32_t > | PoseWithCovarianceStampedMap |
typedef std::map< std::string, uint32_t > | DiagnosticArrayMap |
Static Private Attributes | |
static boost::mutex | callback_mutex_ |
static std::string | do_gpsfix_ = "4007" |
static std::string | do_navsatfix_ = "4007" |
static std::string | do_pose_ = "4007" |
static std::string | do_diagnostics_ = "4014" |
static GPSFixMap | gpsfix_map |
static NavSatFixMap | navsatfix_map |
static PoseWithCovarianceStampedMap | pose_map |
static DiagnosticArrayMap | diagnosticarray_map |
Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class.
Definition at line 207 of file callback_handlers.hpp.
typedef std::multimap<std::string, boost::shared_ptr<AbstractCallbackHandler> > io_comm_rx::CallbackHandlers::CallbackMap |
Key is std::string and represents the ROS message key, value is boost::shared_ptr<CallbackHandler>
Definition at line 213 of file callback_handlers.hpp.
|
private |
Shorthand for the map responsible for matching ROS message identifiers relevant for DiagnosticArray to a uint32_t
Definition at line 307 of file callback_handlers.hpp.
|
private |
Shorthand for the map responsible for matching ROS message identifiers relevant for GPSFix to a uint32_t.
Definition at line 284 of file callback_handlers.hpp.
|
private |
Shorthand for the map responsible for matching ROS message identifiers relevant for NavSatFix to a uint32_t.
Definition at line 291 of file callback_handlers.hpp.
|
private |
Shorthand for the map responsible for matching ROS message identifiers relevant for PoseWithCovarianceStamped to a uint32_t
Definition at line 299 of file callback_handlers.hpp.
|
default |
void io_comm_rx::CallbackHandlers::handle | ( | RxMessage & | rx_message | ) |
Ćalled every time rx_message is found to contain some potentially useful message.
rx_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.
References callback_mutex_, callbackmap_, do_diagnostics_, do_gpsfix_, do_navsatfix_, do_pose_, g_publish_diagnostics, g_publish_gpsfix, g_publish_gpst, g_publish_navsatfix, g_publish_pose, and io_comm_rx::RxMessage::messageID().
Referenced by readCallback().
|
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. rosaic::PVTGeodetic, or nmea_msgs::GPGGA. Note that "typename" could be omitted in the argument.
message_key | The pair's key |
callback | The key's counterpart |
Definition at line 228 of file callback_handlers.hpp.
References io_comm_rx::AbstractCallbackHandler::handle().
Referenced by rosaic_node::ROSaicNode::defineMessages().
void io_comm_rx::CallbackHandlers::readCallback | ( | const uint8_t * | data, |
std::size_t & | size | ||
) |
Searches for Rx messages that could potentially be decoded/parsed/published.
[in] | data | Buffer passed on from AsyncManager class |
[in] | size | Size of the buffer |
Definition at line 269 of file callback_handlers.cpp.
References diagnosticarray_map, do_diagnostics_, do_gpsfix_, do_navsatfix_, do_pose_, io_comm_rx::RxMessage::found(), g_attcoveuler_has_arrived_gpsfix, g_attcoveuler_has_arrived_pose, g_atteuler_has_arrived_gpsfix, g_atteuler_has_arrived_pose, g_cd_condition, g_cd_count, g_cd_mutex, g_cd_received, g_channelstatus_has_arrived_gpsfix, g_dop_has_arrived_gpsfix, g_measepoch_has_arrived_gpsfix, g_poscovgeodetic_has_arrived_gpsfix, g_poscovgeodetic_has_arrived_navsatfix, g_poscovgeodetic_has_arrived_pose, g_publish_diagnostics, g_publish_gpsfix, g_publish_navsatfix, g_publish_pose, g_pvtgeodetic_has_arrived_gpsfix, g_pvtgeodetic_has_arrived_navsatfix, g_pvtgeodetic_has_arrived_pose, g_qualityind_has_arrived_diagnostics, g_receiverstatus_has_arrived_diagnostics, g_response_condition, g_response_mutex, g_response_received, g_rx_tcp_port, g_velcovgeodetic_has_arrived_gpsfix, io_comm_rx::RxMessage::getBlockLength(), io_comm_rx::RxMessage::getCount(), io_comm_rx::RxMessage::getEndBuffer(), io_comm_rx::RxMessage::getPosBuffer(), gpsfix_map, handle(), io_comm_rx::RxMessage::isConnectionDescriptor(), io_comm_rx::RxMessage::isErrorMessage(), io_comm_rx::RxMessage::isNMEA(), io_comm_rx::RxMessage::isResponse(), io_comm_rx::RxMessage::isSBF(), MAX_NMEA_SIZE, io_comm_rx::RxMessage::messageID(), io_comm_rx::RxMessage::messageSize(), navsatfix_map, pose_map, and io_comm_rx::RxMessage::search().
Referenced by io_comm_rx::Comm_IO::setManager().
|
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 265 of file callback_handlers.hpp.
Referenced by handle().
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 257 of file callback_handlers.hpp.
Referenced by rosaic_node::ROSaicNode::defineMessages(), and handle().
|
staticprivate |
All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static
Definition at line 311 of file callback_handlers.hpp.
Referenced by readCallback().
|
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 281 of file callback_handlers.hpp.
Referenced by handle(), and readCallback().
|
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 269 of file callback_handlers.hpp.
Referenced by handle(), and readCallback().
|
staticprivate |
Determines which of the SBF blocks necessary for the sensor_msgs::NavSatFix ROS message arrives last and thus launches its construction
Definition at line 273 of file callback_handlers.hpp.
Referenced by handle(), and readCallback().
|
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 277 of file callback_handlers.hpp.
Referenced by handle(), and readCallback().
|
staticprivate |
All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static
Definition at line 288 of file callback_handlers.hpp.
Referenced by readCallback().
|
staticprivate |
All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static
Definition at line 295 of file callback_handlers.hpp.
Referenced by readCallback().
|
staticprivate |
All instances of the CallbackHandlers class shall have access to the map without reinitializing it, hence static
Definition at line 303 of file callback_handlers.hpp.
Referenced by readCallback().