Class PriorityMux
Defined in File priority_mux_base.h
Inheritance Relationships
Base Type
public cras::HasLogger
Class Documentation
-
class PriorityMux : public cras::HasLogger
A class for priority-based muxing of topics.
This class provides the functionality for priority-based muxing of topics. It allows to control access to one or more output topics which several input topics are aiming for. Priorities are assigned to each input topic to decide which one gets access to its desired output. A validity period is also assigned to each input topic which needs to be renewed whenever a message is received from the topic. An input topic can be disabled explicitly via a topic.
Public Types
-
typedef ::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.- Param name:
[in] Name of the timer (subsequent calls with the same name will cancel the preceding requests).
- Param timeout:
[in] The time after which
update()should be called.
Public Functions
-
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.
- Parameters:
topicConfigs – [in] Configurations of input topics.
lockConfigs – [in] Configurations of lock topics.
setTimerFn – [in] The function to call when the mux needs to schedule a call to
update()after some time.now – [in] Current time.
log – [in] The CRAS logger to use for printing log messages.
noneTopic – [in] Virtual name of a topic reported as selected when no priority is active.
nonePriority – [in] Priority level signalling that no priority is active.
-
virtual ~PriorityMux()
-
virtual bool cb(const ::std::string &inTopic, const ::ros::Time &stamp, const ::ros::Time &now)
Callback function run when input topic message is received.
- Parameters:
inTopic – [in] Name of the input topic.
stamp – [in] ROS time stamp of the message.
now – [in] Current ROS time.
- Returns:
True if the input message should be relayed to its output topic.
-
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.
- Parameters:
inTopic – [in] Name of the input topic to disable/enable.
stamp – [in] ROS time stamp of the message.
disable – [in] Whether to disable the input topic or enable it (
truemeans disable).now – [in] Current ROS time.
-
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.
- Parameters:
topic – [in] Name of the lock topic.
stamp – [in] ROS time stamp of the message.
locked – [in] Whether to lock the lock or unlock it (
truemeans lock).now – [in] Current ROS time.
-
virtual void update(const ::ros::Time &now)
Updates the mux after changes have been made to some of its internal state.
- Parameters:
now – [in] Current ROS time.
-
virtual void reset(const ::ros::Time &now)
Resets the mux to its initial state.
- Parameters:
now – [in] Current time.
-
const ::std::unordered_map<::std::string, ::std::string> &getLastSelectedTopics() const
Return the last selected topic for each output topic.
- Returns:
The last selected topic for each output topic.
-
int getActivePriority() const
Return the active priority level.
- Returns:
The active priority level.
-
bool isDisabled(const ::std::string &inTopic, const ::ros::Time &now)
Whether the given topic is currently disabled.
- Parameters:
inTopic – [in] The topic name.
now – [in] Current time.
- Returns:
Whether the topic is disabled.
Protected Functions
-
int getHighestLockedPriority(const ::ros::Time &now)
Gets the highest locked priority.
- Parameters:
now – [in] Current ROS time.
- Returns:
The highest locked priority.
Protected Attributes
-
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig> topicConfigs
Configurations of input topics.
-
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig> lockConfigs
Configurations of lock topics.
-
SetTimerFn setTimer
The function to call when the mux needs to schedule a call to
update()after some time.
-
::std::map<::std::pair<int, ::std::string>, ::ros::Time> lastReceiveStamps
The timestamps of the last received message for each input topic.
-
::std::map<::std::pair<int, ::std::string>, ::ros::Time> disabledStamps
The timestamps of the last received disable message for each input topic.
-
::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>, bool> lockStates
Current lock status of each lock topic (whether the lock is explicitly locked or not).
-
::std::string noneTopic
Virtual name of a topic reported as selected when no priority is active.
-
int nonePriority
Priority level signalling that no priority is active.
-
int lastActivePriority
The currently active priority level.
-
::std::unordered_map<::std::string, ::std::string> lastSelectedTopics
The currently selected topic for each output topic.
-
typedef ::std::function<void(const ::std::string &name, const ::ros::Duration &timeout)> SetTimerFn