Go to the documentation of this file.
15 #include <unordered_map>
26 namespace priority_mux
92 typedef ::std::function<void(const ::std::string& name, const ::ros::Duration& timeout)>
SetTimerFn;
106 const ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig>&
lockConfigs,
107 const SetTimerFn& setTimerFn, const ::ros::Time& now, const ::cras::LogHelperPtr&
log,
120 virtual bool cb(const ::std::string& inTopic, const ::ros::Time& stamp, const ::ros::Time& now);
130 virtual void disableCb(const ::std::string& inTopic, const ::ros::Time& stamp,
bool disable, const ::ros::Time& now);
140 virtual void lockCb(const ::std::string& topic, const ::ros::Time& stamp,
bool locked, const ::ros::Time& now);
147 virtual void update(const ::ros::Time& now);
154 virtual void reset(const ::ros::Time& now);
176 bool isDisabled(const ::std::string& inTopic, const ::ros::Time& now);
188 ::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig>
topicConfigs;
191 ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig>
lockConfigs;
212 ::std::map<::std::pair<int, ::std::string>,
bool>
lockStates;
bool isDisabled(const ::std::string &inTopic, const ::ros::Time &now)
::std::string name
The human-readable name of the config.
Configuration of a lock topic for the mux.
int priority
The priority for the topic. Usually is a positive number.
virtual bool cb(const ::std::string &inTopic, const ::ros::Time &stamp, const ::ros::Time &now)
Callback function run when input topic message is received.
void resetImpl(const ::ros::Time &now)
Reset the mux to its original state.
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > lockConfigs
Configurations of lock topics.
::std::string noneTopic
Virtual name of a topic reported as selected when no priority is active.
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > topicConfigs
Configurations of input topics.
::std::string topic
The topic associated with the lock.
size_t numSubscribersToWait
virtual void disableCb(const ::std::string &inTopic, const ::ros::Time &stamp, bool disable, const ::ros::Time &now)
Callback function to disable/enable an input topic.
Configuration of an output topic for the mux.
::std::string inTopic
The input topic.
int getHighestLockedPriority(const ::ros::Time &now)
Gets the highest locked priority.
::std::map<::std::pair< int, ::std::string >, ::ros::Time > lastLockStamps
The timestamps of the last received lock message for each lock topic.
::std::map<::std::pair< int, ::std::string >, ::ros::Time > lastReceiveStamps
The timestamps of the last received message for each input topic.
::ros::WallDuration subscriberConnectDelay
A class for priority-based muxing of topics.
SetTimerFn setTimer
The function to call when the mux needs to schedule a call to update() after some time.
int priority
The priority for the lock. Usually is a positive number.
PriorityMux(const ::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > &topicConfigs, const ::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > &lockConfigs, const SetTimerFn &setTimerFn, const ::ros::Time &now, const ::cras::LogHelperPtr &log, const ::std::string &noneTopic="__none", int nonePriority=0)
Constructs a PriorityMux object.
int lastActivePriority
The currently active priority level.
::std::string name
The human-readable name of the config.
Configuration of an input to the mux.
int getActivePriority() const
Return the active priority level.
::ros::Duration timeout
How long do messages on this topic keep the priority active.
::std::function< void(const ::std::string &name, const ::ros::Duration &timeout)> SetTimerFn
The function to call when the mux needs to schedule a call to update() after some time.
::std::map<::std::pair< int, ::std::string >, bool > lockStates
Current lock status of each lock topic (whether the lock is explicitly locked or not).
virtual void lockCb(const ::std::string &topic, const ::ros::Time &stamp, bool locked, const ::ros::Time &now)
Callback function run when a lock message is received.
::cras::optional< bool > forceLatch
::std::unordered_map<::std::string, ::std::string > lastSelectedTopics
The currently selected topic for each output topic.
size_t queueSize
Queue size for the subscriber.
::std::string topic
The output topic.
virtual void reset(const ::ros::Time &now)
Resets the mux to its initial state.
::std::map<::std::pair< int, ::std::string >, ::ros::Time > disabledStamps
The timestamps of the last received disable message for each input topic.
size_t queueSize
Queue size for the publisher.
const ::std::unordered_map<::std::string, ::std::string > & getLastSelectedTopics() const
Return the last selected topic for each output topic.
virtual void update(const ::ros::Time &now)
Updates the mux after changes have been made to some of its internal state.
::std::string outTopic
The output topic.
int nonePriority
Priority level signalling that no priority is active.
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18