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 
114 {
115 protected:
116  void onInit() override;
117 
123  virtual void cb(const ::std::string& inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
124 
130  virtual void lockCb(const ::std::string& topic, const ::ros::MessageEvent<::std_msgs::Bool const>& event);
131 
138  virtual void disableCb(const ::std::string& inTopic,
139  const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
140 
146  virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
147 
152  void publishChanges();
153 
159  void onTimeout(const ::std::string& name, const ::ros::TimerEvent&);
160 
166  void setTimer(const ::std::string& name, const ::ros::Duration& timeout);
167 
171  void reset();
172 
174  ::std::unique_ptr<::cras::PriorityMux> mux;
175 
177  ::std::list<::ros::Subscriber> subscribers;
178 
180  ::std::unordered_map<::std::string, ::ros::Publisher> publishers;
181 
184 
186  ::std::unordered_map<::std::string, ::ros::Publisher> selectedPublishers;
187 
190 
192  ::std::unordered_map<::std::string, ::ros::Timer> timers;
193 
195  ::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig> topicConfigs;
196 
198  ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig> lockConfigs;
199 
201  std::unordered_map<std::string, ::cras::priority_mux::OutputTopicConfig> outTopicConfigs;
202 
204  ::std::unordered_set<::std::string> outTopics;
205 
207  ::cras::optional<int> lastActivePriority;
208 
210  ::std::unordered_map<::std::string, ::std::string> lastSelectedTopics;
211 
213  ::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter>> beforeDisableMessages;
214 
216  ::std::unordered_set<::std::string> beforeDisableMessagesWithHeader;
217 
219  size_t queueSize {10u};
220 
222  bool tcpNoDelay {false};
223 };
224 
225 }
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:489
cras::PriorityMuxNodelet::onInit
void onInit() override
Definition: priority_mux.cpp:36
cras::PriorityMuxNodelet::activePriorityPub
::ros::Publisher activePriorityPub
Publisher for active priority.
Definition: priority_mux.h:183
cras::PriorityMuxNodelet::queueSize
size_t queueSize
Queue size of all publishers and subscribers.
Definition: priority_mux.h:219
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:376
cras::PriorityMuxNodelet::lastActivePriority
::cras::optional< int > lastActivePriority
The active priority after the last publishChanges() call.
Definition: priority_mux.h:207
cras::PriorityMuxNodelet
Priority-based muxer nodelet for topics.
Definition: priority_mux.h:113
cras::PriorityMuxNodelet::lastSelectedTopics
::std::unordered_map<::std::string, ::std::string > lastSelectedTopics
The selected output topics after the last publishChanges() call.
Definition: priority_mux.h:210
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:437
cras::PriorityMuxNodelet::beforeDisableMessagesWithHeader
::std::unordered_set<::std::string > beforeDisableMessagesWithHeader
Cached list of "before disable" messages that have a Header.
Definition: priority_mux.h:216
priority_mux_base.h
Priority-based muxer for topics.
cras::PriorityMuxNodelet::resetSub
::ros::Subscriber resetSub
Subscriber for reset topic.
Definition: priority_mux.h:189
cras::PriorityMuxNodelet::lockConfigs
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > lockConfigs
Configurations of lock topics.
Definition: priority_mux.h:198
cras::PriorityMuxNodelet::topicConfigs
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > topicConfigs
Configurations of input topics.
Definition: priority_mux.h:195
cras::PriorityMuxNodelet::mux
::std::unique_ptr<::cras::PriorityMux > mux
Mux instance.
Definition: priority_mux.h:174
ros::Publisher
cras::PriorityMuxNodelet::outTopicConfigs
std::unordered_map< std::string, ::cras::priority_mux::OutputTopicConfig > outTopicConfigs
Configurations of output topics.
Definition: priority_mux.h:201
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:553
cras::PriorityMuxNodelet::publishers
::std::unordered_map<::std::string, ::ros::Publisher > publishers
Map of output topic and the associated publisher.
Definition: priority_mux.h:180
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:213
cras::PriorityMuxNodelet::tcpNoDelay
bool tcpNoDelay
Whether tcpNoDelay() flag should be set for all subscribers.
Definition: priority_mux.h:222
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:186
cras::Nodelet
cras::PriorityMuxNodelet::reset
void reset()
Reset the mux to its initial state.
Definition: priority_mux.cpp:538
cras::PriorityMuxNodelet::outTopics
::std::unordered_set<::std::string > outTopics
All output topic names.
Definition: priority_mux.h:204
cras::PriorityMuxNodelet::timers
::std::unordered_map<::std::string, ::ros::Timer > timers
Map of timer names and the timers.
Definition: priority_mux.h:192
cras::PriorityMuxNodelet::disableCb
virtual void disableCb(const ::std::string &inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback method triggered when a disable message is received.
Definition: priority_mux.cpp:444
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:518
ros::Subscriber
cras::PriorityMuxNodelet::subscribers
::std::list<::ros::Subscriber > subscribers
List of subscribers. Just for keeping them alive.
Definition: priority_mux.h:177
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:525
nodelet_utils.hpp


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:49:11