Go to the documentation of this file.
16 #include <unordered_map>
17 #include <unordered_set>
20 #include <std_msgs/Bool.h>
21 #include <topic_tools/shape_shifter.h>
127 virtual void cb(const ::std::string& inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
134 virtual void lockCb(const ::std::string& topic, const ::ros::MessageEvent<::std_msgs::Bool const>& event);
145 virtual void disableCb(const ::std::string& inTopic,
147 const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
154 virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
167 void onTimeout(const ::std::string& name, const ::ros::TimerEvent&);
174 void setTimer(const ::std::string& name, const ::ros::Duration& timeout);
182 ::std::unique_ptr<::cras::PriorityMux>
mux;
188 ::std::unordered_map<::std::string, ::ros::Publisher>
publishers;
200 ::std::unordered_map<::std::string, ::ros::Timer>
timers;
203 ::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig>
topicConfigs;
206 ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig>
lockConfigs;
209 std::unordered_map<std::string, ::cras::priority_mux::OutputTopicConfig>
outTopicConfigs;
Tools for more convenient working with ShapeShifter objects.
void publishChanges()
Check what changed from the last publishChanges() call and if there are changes, publish them (active...
::ros::Publisher activePriorityPub
Publisher for active priority.
virtual void disableCb(const ::std::string &inTopic, bool invert, const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback method triggered when a disable message is received.
size_t queueSize
Queue size of all publishers and subscribers.
virtual void cb(const ::std::string &inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback method triggered when a message is received on the input topic.
::cras::optional< int > lastActivePriority
The active priority after the last publishChanges() call.
Priority-based muxer nodelet for topics.
::std::unordered_map<::std::string, ::std::string > lastSelectedTopics
The selected output topics after the last publishChanges() call.
virtual void lockCb(const ::std::string &topic, const ::ros::MessageEvent<::std_msgs::Bool const > &event)
Callback method triggered when a lock message is received.
::std::unordered_set<::std::string > beforeDisableMessagesWithHeader
Cached list of "before disable" messages that have a Header.
Priority-based muxer for topics.
::ros::Subscriber resetSub
Subscriber for reset topic.
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > lockConfigs
Configurations of lock topics.
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > topicConfigs
Configurations of input topics.
::std::unique_ptr<::cras::PriorityMux > mux
Mux instance.
std::unordered_map< std::string, ::cras::priority_mux::OutputTopicConfig > outTopicConfigs
Configurations of output topics.
virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback method triggered when a reset message is received.
::std::unordered_map<::std::string, ::ros::Publisher > publishers
Map of output topic and the associated publisher.
::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter > > beforeDisableMessages
The messages to be injected into the mux right before a topic is disabled.
bool tcpNoDelay
Whether tcpNoDelay() flag should be set for all subscribers.
::std::unordered_map<::std::string, ::ros::Publisher > selectedPublishers
Map of publishers of the topics announcing currently selected publishers.
void reset()
Reset the mux to its initial state.
::std::unordered_set<::std::string > outTopics
All output topic names.
::std::unordered_map<::std::string, ::ros::Timer > timers
Map of timer names and the timers.
void onTimeout(const ::std::string &name, const ::ros::TimerEvent &)
Method triggered on timer timeout. This should update the mux and check for changes.
::std::list<::ros::Subscriber > subscribers
List of subscribers. Just for keeping them alive.
void setTimer(const ::std::string &name, const ::ros::Duration &timeout)
Set a timer that will call onTimeout() after the specified time.
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18