A class for priority-based muxing of topics. More...
#include <priority_mux_base.h>
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. More... | |
Public Member Functions | |
virtual bool | cb (const ::std::string &inTopic, const ::ros::Time &stamp, const ::ros::Time &now) |
Callback function run when input topic message is received. More... | |
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. More... | |
int | getActivePriority () const |
Return the active priority level. More... | |
const ::std::unordered_map<::std::string, ::std::string > & | getLastSelectedTopics () const |
Return the last selected topic for each output topic. More... | |
bool | isDisabled (const ::std::string &inTopic, const ::ros::Time &now) |
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. More... | |
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. More... | |
virtual void | reset (const ::ros::Time &now) |
Resets the mux to its initial state. More... | |
virtual void | update (const ::ros::Time &now) |
Updates the mux after changes have been made to some of its internal state. More... | |
![]() | |
::cras::LogHelperConstPtr | getCrasLogger () const |
HasLogger (const ::cras::LogHelperPtr &log) | |
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
Protected Member Functions | |
int | getHighestLockedPriority (const ::ros::Time &now) |
Gets the highest locked priority. More... | |
Protected Attributes | |
::std::map<::std::pair< int, ::std::string >, ::ros::Time > | disabledStamps |
The timestamps of the last received disable message for each input topic. More... | |
int | lastActivePriority |
The currently active priority level. More... | |
::std::map<::std::pair< int, ::std::string >, ::ros::Time > | lastLockStamps |
The timestamps of the last received lock message for each lock topic. More... | |
::std::map<::std::pair< int, ::std::string >, ::ros::Time > | lastReceiveStamps |
The timestamps of the last received message for each input topic. More... | |
::std::unordered_map<::std::string, ::std::string > | lastSelectedTopics |
The currently selected topic for each output topic. More... | |
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig > | lockConfigs |
Configurations of lock topics. More... | |
::std::map<::std::pair< int, ::std::string >, bool > | lockStates |
Current lock status of each lock topic (whether the lock is explicitly locked or not). More... | |
int | nonePriority |
Priority level signalling that no priority is active. More... | |
::std::string | noneTopic |
Virtual name of a topic reported as selected when no priority is active. More... | |
SetTimerFn | setTimer |
The function to call when the mux needs to schedule a call to update() after some time. More... | |
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > | topicConfigs |
Configurations of input topics. More... | |
![]() | |
::cras::LogHelperPtr | log |
Private Member Functions | |
void | resetImpl (const ::ros::Time &now) |
Reset the mux to its original state. More... | |
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.
Definition at line 83 of file priority_mux_base.h.
typedef ::std::function<void(const ::std::string& name, const ::ros::Duration& timeout)> cras::PriorityMux::SetTimerFn |
The function to call when the mux needs to schedule a call to update()
after some time.
[in] | name | Name of the timer (subsequent calls with the same name will cancel the preceding requests). |
[in] | timeout | The time after which update() should be called. |
Definition at line 92 of file priority_mux_base.h.
cras::PriorityMux::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.
[in] | topicConfigs | Configurations of input topics. |
[in] | lockConfigs | Configurations of lock topics. |
[in] | setTimerFn | The function to call when the mux needs to schedule a call to update() after some time. |
[in] | now | Current time. |
[in] | log | The CRAS logger to use for printing log messages. |
[in] | noneTopic | Virtual name of a topic reported as selected when no priority is active. |
[in] | nonePriority | Priority level signalling that no priority is active. |
Definition at line 21 of file priority_mux_base.cpp.
|
virtual |
Callback function run when input topic message is received.
[in] | inTopic | Name of the input topic. |
[in] | stamp | ROS time stamp of the message. |
[in] | now | Current ROS time. |
Definition at line 43 of file priority_mux_base.cpp.
|
virtual |
Callback function to disable/enable an input topic.
[in] | inTopic | Name of the input topic to disable/enable. |
[in] | stamp | ROS time stamp of the message. |
[in] | disable | Whether to disable the input topic or enable it (true means disable). |
[in] | now | Current ROS time. |
Definition at line 78 of file priority_mux_base.cpp.
int cras::PriorityMux::getActivePriority | ( | ) | const |
Return the active priority level.
Definition at line 220 of file priority_mux_base.cpp.
Gets the highest locked priority.
[in] | now | Current ROS time. |
Definition at line 195 of file priority_mux_base.cpp.
const std::unordered_map< std::string, std::string > & cras::PriorityMux::getLastSelectedTopics | ( | ) | const |
Return the last selected topic for each output topic.
Definition at line 215 of file priority_mux_base.cpp.
bool cras::PriorityMux::isDisabled | ( | const ::std::string & | inTopic, |
const ::ros::Time & | now | ||
) |
Whether the given topic is currently disabled.
[in] | inTopic | The topic name. |
[in] | now | Current time. |
Definition at line 250 of file priority_mux_base.cpp.
|
virtual |
Callback function run when a lock message is received.
[in] | topic | Name of the lock topic. |
[in] | stamp | ROS time stamp of the message. |
[in] | locked | Whether to lock the lock or unlock it (true means lock). |
[in] | now | Current ROS time. |
Definition at line 110 of file priority_mux_base.cpp.
|
virtual |
Resets the mux to its initial state.
[in] | now | Current time. |
Definition at line 225 of file priority_mux_base.cpp.
|
private |
Reset the mux to its original state.
[in] | now | Current time. |
Definition at line 230 of file priority_mux_base.cpp.
|
virtual |
Updates the mux after changes have been made to some of its internal state.
[in] | now | Current ROS time. |
Definition at line 136 of file priority_mux_base.cpp.
|
protected |
The timestamps of the last received disable message for each input topic.
Definition at line 204 of file priority_mux_base.h.
|
protected |
The currently active priority level.
Definition at line 219 of file priority_mux_base.h.
|
protected |
The timestamps of the last received lock message for each lock topic.
Definition at line 207 of file priority_mux_base.h.
|
protected |
The timestamps of the last received message for each input topic.
Definition at line 201 of file priority_mux_base.h.
|
protected |
The currently selected topic for each output topic.
Definition at line 222 of file priority_mux_base.h.
|
protected |
Configurations of lock topics.
Definition at line 189 of file priority_mux_base.h.
|
protected |
Current lock status of each lock topic (whether the lock is explicitly locked or not).
Definition at line 210 of file priority_mux_base.h.
|
protected |
Priority level signalling that no priority is active.
Definition at line 216 of file priority_mux_base.h.
|
protected |
Virtual name of a topic reported as selected when no priority is active.
Definition at line 213 of file priority_mux_base.h.
|
protected |
The function to call when the mux needs to schedule a call to update()
after some time.
Definition at line 192 of file priority_mux_base.h.
|
protected |
Configurations of input topics.
Definition at line 186 of file priority_mux_base.h.