priority_mux.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <list>
13 #include <map>
14 #include <memory>
15 #include <string>
16 #include <unordered_map>
17 #include <unordered_set>
18 #include <utility>
19 
20 #include <std_msgs/Bool.h>
21 #include <topic_tools/shape_shifter.h>
22 
27 
28 namespace cras
29 {
30 
118 {
119 protected:
120  void onInit() override;
121 
127  virtual void cb(const ::std::string& inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
128 
134  virtual void lockCb(const ::std::string& topic, const ::ros::MessageEvent<::std_msgs::Bool const>& event);
135 
145  virtual void disableCb(const ::std::string& inTopic,
146  bool invert,
147  const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
148 
154  virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
155 
160  void publishChanges();
161 
167  void onTimeout(const ::std::string& name, const ::ros::TimerEvent&);
168 
174  void setTimer(const ::std::string& name, const ::ros::Duration& timeout);
175 
179  void reset();
180 
182  ::std::unique_ptr<::cras::PriorityMux> mux;
183 
185  ::std::list<::ros::Subscriber> subscribers;
186 
188  ::std::unordered_map<::std::string, ::ros::Publisher> publishers;
189 
192 
194  ::std::unordered_map<::std::string, ::ros::Publisher> selectedPublishers;
195 
198 
200  ::std::unordered_map<::std::string, ::ros::Timer> timers;
201 
203  ::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig> topicConfigs;
204 
206  ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig> lockConfigs;
207 
209  std::unordered_map<std::string, ::cras::priority_mux::OutputTopicConfig> outTopicConfigs;
210 
212  ::std::unordered_set<::std::string> outTopics;
213 
215  ::cras::optional<int> lastActivePriority;
216 
218  ::std::unordered_map<::std::string, ::std::string> lastSelectedTopics;
219 
221  ::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter>> beforeDisableMessages;
222 
224  ::std::unordered_set<::std::string> beforeDisableMessagesWithHeader;
225 
227  size_t queueSize {10u};
228 
230  bool tcpNoDelay {false};
231 };
232 
233 }
optional.hpp
cras
shape_shifter.h
Tools for more convenient working with ShapeShifter objects.
cras::PriorityMuxNodelet::publishChanges
void publishChanges()
Check what changed from the last publishChanges() call and if there are changes, publish them (active...
Definition: priority_mux.cpp:501
cras::PriorityMuxNodelet::onInit
void onInit() override
Definition: priority_mux.cpp:37
cras::PriorityMuxNodelet::activePriorityPub
::ros::Publisher activePriorityPub
Publisher for active priority.
Definition: priority_mux.h:191
cras::PriorityMuxNodelet::disableCb
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.
Definition: priority_mux.cpp:452
cras::PriorityMuxNodelet::queueSize
size_t queueSize
Queue size of all publishers and subscribers.
Definition: priority_mux.h:227
cras::PriorityMuxNodelet::cb
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.
Definition: priority_mux.cpp:384
cras::PriorityMuxNodelet::lastActivePriority
::cras::optional< int > lastActivePriority
The active priority after the last publishChanges() call.
Definition: priority_mux.h:215
cras::PriorityMuxNodelet
Priority-based muxer nodelet for topics.
Definition: priority_mux.h:117
cras::PriorityMuxNodelet::lastSelectedTopics
::std::unordered_map<::std::string, ::std::string > lastSelectedTopics
The selected output topics after the last publishChanges() call.
Definition: priority_mux.h:218
cras::PriorityMuxNodelet::lockCb
virtual void lockCb(const ::std::string &topic, const ::ros::MessageEvent<::std_msgs::Bool const > &event)
Callback method triggered when a lock message is received.
Definition: priority_mux.cpp:445
cras::PriorityMuxNodelet::beforeDisableMessagesWithHeader
::std::unordered_set<::std::string > beforeDisableMessagesWithHeader
Cached list of "before disable" messages that have a Header.
Definition: priority_mux.h:224
priority_mux_base.h
Priority-based muxer for topics.
cras::PriorityMuxNodelet::resetSub
::ros::Subscriber resetSub
Subscriber for reset topic.
Definition: priority_mux.h:197
cras::PriorityMuxNodelet::lockConfigs
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > lockConfigs
Configurations of lock topics.
Definition: priority_mux.h:206
cras::PriorityMuxNodelet::topicConfigs
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > topicConfigs
Configurations of input topics.
Definition: priority_mux.h:203
cras::PriorityMuxNodelet::mux
::std::unique_ptr<::cras::PriorityMux > mux
Mux instance.
Definition: priority_mux.h:182
ros::Publisher
cras::PriorityMuxNodelet::outTopicConfigs
std::unordered_map< std::string, ::cras::priority_mux::OutputTopicConfig > outTopicConfigs
Configurations of output topics.
Definition: priority_mux.h:209
cras::PriorityMuxNodelet::resetCb
virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback method triggered when a reset message is received.
Definition: priority_mux.cpp:565
cras::PriorityMuxNodelet::publishers
::std::unordered_map<::std::string, ::ros::Publisher > publishers
Map of output topic and the associated publisher.
Definition: priority_mux.h:188
cras::PriorityMuxNodelet::beforeDisableMessages
::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter > > beforeDisableMessages
The messages to be injected into the mux right before a topic is disabled.
Definition: priority_mux.h:221
cras::PriorityMuxNodelet::tcpNoDelay
bool tcpNoDelay
Whether tcpNoDelay() flag should be set for all subscribers.
Definition: priority_mux.h:230
cras::PriorityMuxNodelet::selectedPublishers
::std::unordered_map<::std::string, ::ros::Publisher > selectedPublishers
Map of publishers of the topics announcing currently selected publishers.
Definition: priority_mux.h:194
cras::Nodelet
cras::PriorityMuxNodelet::reset
void reset()
Reset the mux to its initial state.
Definition: priority_mux.cpp:550
cras::PriorityMuxNodelet::outTopics
::std::unordered_set<::std::string > outTopics
All output topic names.
Definition: priority_mux.h:212
cras::PriorityMuxNodelet::timers
::std::unordered_map<::std::string, ::ros::Timer > timers
Map of timer names and the timers.
Definition: priority_mux.h:200
cras::PriorityMuxNodelet::onTimeout
void onTimeout(const ::std::string &name, const ::ros::TimerEvent &)
Method triggered on timer timeout. This should update the mux and check for changes.
Definition: priority_mux.cpp:530
ros::Subscriber
cras::PriorityMuxNodelet::subscribers
::std::list<::ros::Subscriber > subscribers
List of subscribers. Just for keeping them alive.
Definition: priority_mux.h:185
cras::PriorityMuxNodelet::setTimer
void setTimer(const ::std::string &name, const ::ros::Duration &timeout)
Set a timer that will call onTimeout() after the specified time.
Definition: priority_mux.cpp:537
nodelet_utils.hpp


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18