Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
cras::PriorityMux Class Reference

A class for priority-based muxing of topics. More...

#include <priority_mux_base.h>

Inheritance diagram for cras::PriorityMux:
Inheritance graph
[legend]

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...
 
- Public Member Functions inherited from cras::HasLogger
::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::TimedisabledStamps
 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::TimelastLockStamps
 The timestamps of the last received lock message for each lock topic. More...
 
::std::map<::std::pair< int, ::std::string >, ::ros::TimelastReceiveStamps
 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::LockConfiglockConfigs
 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::TopicConfigtopicConfigs
 Configurations of input topics. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Private Member Functions

void resetImpl (const ::ros::Time &now)
 Reset the mux to its original state. More...
 

Detailed Description

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.

Member Typedef Documentation

◆ SetTimerFn

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.

Parameters
[in]nameName of the timer (subsequent calls with the same name will cancel the preceding requests).
[in]timeoutThe time after which update() should be called.

Definition at line 92 of file priority_mux_base.h.

Constructor & Destructor Documentation

◆ PriorityMux()

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.

Parameters
[in]topicConfigsConfigurations of input topics.
[in]lockConfigsConfigurations of lock topics.
[in]setTimerFnThe function to call when the mux needs to schedule a call to update() after some time.
[in]nowCurrent time.
[in]logThe CRAS logger to use for printing log messages.
[in]noneTopicVirtual name of a topic reported as selected when no priority is active.
[in]nonePriorityPriority level signalling that no priority is active.

Definition at line 21 of file priority_mux_base.cpp.

Member Function Documentation

◆ cb()

bool cras::PriorityMux::cb ( const ::std::string &  inTopic,
const ::ros::Time stamp,
const ::ros::Time now 
)
virtual

Callback function run when input topic message is received.

Parameters
[in]inTopicName of the input topic.
[in]stampROS time stamp of the message.
[in]nowCurrent ROS time.
Returns
True if the input message should be relayed to its output topic.

Definition at line 43 of file priority_mux_base.cpp.

◆ disableCb()

void cras::PriorityMux::disableCb ( const ::std::string &  inTopic,
const ::ros::Time stamp,
bool  disable,
const ::ros::Time now 
)
virtual

Callback function to disable/enable an input topic.

Parameters
[in]inTopicName of the input topic to disable/enable.
[in]stampROS time stamp of the message.
[in]disableWhether to disable the input topic or enable it (true means disable).
[in]nowCurrent ROS time.

Definition at line 78 of file priority_mux_base.cpp.

◆ getActivePriority()

int cras::PriorityMux::getActivePriority ( ) const

Return the active priority level.

Returns
The active priority level.

Definition at line 220 of file priority_mux_base.cpp.

◆ getHighestLockedPriority()

int cras::PriorityMux::getHighestLockedPriority ( const ::ros::Time now)
protected

Gets the highest locked priority.

Parameters
[in]nowCurrent ROS time.
Returns
The highest locked priority.

Definition at line 195 of file priority_mux_base.cpp.

◆ getLastSelectedTopics()

const std::unordered_map< std::string, std::string > & cras::PriorityMux::getLastSelectedTopics ( ) const

Return the last selected topic for each output topic.

Returns
The last selected topic for each output topic.

Definition at line 215 of file priority_mux_base.cpp.

◆ isDisabled()

bool cras::PriorityMux::isDisabled ( const ::std::string &  inTopic,
const ::ros::Time now 
)

Whether the given topic is currently disabled.

Parameters
[in]inTopicThe topic name.
[in]nowCurrent time.
Returns
Whether the topic is disabled.

Definition at line 250 of file priority_mux_base.cpp.

◆ lockCb()

void cras::PriorityMux::lockCb ( const ::std::string &  topic,
const ::ros::Time stamp,
bool  locked,
const ::ros::Time now 
)
virtual

Callback function run when a lock message is received.

Parameters
[in]topicName of the lock topic.
[in]stampROS time stamp of the message.
[in]lockedWhether to lock the lock or unlock it (true means lock).
[in]nowCurrent ROS time.

Definition at line 110 of file priority_mux_base.cpp.

◆ reset()

void cras::PriorityMux::reset ( const ::ros::Time now)
virtual

Resets the mux to its initial state.

Parameters
[in]nowCurrent time.

Definition at line 225 of file priority_mux_base.cpp.

◆ resetImpl()

void cras::PriorityMux::resetImpl ( const ::ros::Time now)
private

Reset the mux to its original state.

Parameters
[in]nowCurrent time.

Definition at line 230 of file priority_mux_base.cpp.

◆ update()

void cras::PriorityMux::update ( const ::ros::Time now)
virtual

Updates the mux after changes have been made to some of its internal state.

Parameters
[in]nowCurrent ROS time.

Definition at line 136 of file priority_mux_base.cpp.

Member Data Documentation

◆ disabledStamps

::std::map<::std::pair<int, ::std::string>, ::ros::Time> cras::PriorityMux::disabledStamps
protected

The timestamps of the last received disable message for each input topic.

Definition at line 204 of file priority_mux_base.h.

◆ lastActivePriority

int cras::PriorityMux::lastActivePriority
protected

The currently active priority level.

Definition at line 219 of file priority_mux_base.h.

◆ lastLockStamps

::std::map<::std::pair<int, ::std::string>, ::ros::Time> cras::PriorityMux::lastLockStamps
protected

The timestamps of the last received lock message for each lock topic.

Definition at line 207 of file priority_mux_base.h.

◆ lastReceiveStamps

::std::map<::std::pair<int, ::std::string>, ::ros::Time> cras::PriorityMux::lastReceiveStamps
protected

The timestamps of the last received message for each input topic.

Definition at line 201 of file priority_mux_base.h.

◆ lastSelectedTopics

::std::unordered_map<::std::string, ::std::string> cras::PriorityMux::lastSelectedTopics
protected

The currently selected topic for each output topic.

Definition at line 222 of file priority_mux_base.h.

◆ lockConfigs

::std::unordered_map<::std::string, ::cras::priority_mux::LockConfig> cras::PriorityMux::lockConfigs
protected

Configurations of lock topics.

Definition at line 189 of file priority_mux_base.h.

◆ lockStates

::std::map<::std::pair<int, ::std::string>, bool> cras::PriorityMux::lockStates
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.

◆ nonePriority

int cras::PriorityMux::nonePriority
protected

Priority level signalling that no priority is active.

Definition at line 216 of file priority_mux_base.h.

◆ noneTopic

::std::string cras::PriorityMux::noneTopic
protected

Virtual name of a topic reported as selected when no priority is active.

Definition at line 213 of file priority_mux_base.h.

◆ setTimer

SetTimerFn cras::PriorityMux::setTimer
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.

◆ topicConfigs

::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig> cras::PriorityMux::topicConfigs
protected

Configurations of input topics.

Definition at line 186 of file priority_mux_base.h.


The documentation for this class was generated from the following files:


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