Protected Member Functions | Protected Attributes | List of all members
cras::PriorityMuxNodelet Class Reference

Priority-based muxer nodelet for topics. More...

#include <priority_mux.h>

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

Protected Member Functions

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. More...
 
virtual void disableCb (const ::std::string &inTopic, const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
 Callback method triggered when a disable message is received. More...
 
virtual void lockCb (const ::std::string &topic, const ::ros::MessageEvent<::std_msgs::Bool const > &event)
 Callback method triggered when a lock message is received. More...
 
void onInit () override
 
void onTimeout (const ::std::string &name, const ::ros::TimerEvent &)
 Method triggered on timer timeout. This should update the mux and check for changes. More...
 
void publishChanges ()
 Check what changed from the last publishChanges() call and if there are changes, publish them (active priority, selected output topics etc.). More...
 
void reset ()
 Reset the mux to its initial state. More...
 
virtual void resetCb (const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
 Callback method triggered when a reset message is received. More...
 
void setTimer (const ::std::string &name, const ::ros::Duration &timeout)
 Set a timer that will call onTimeout() after the specified time. More...
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (ros::AdvertiseOptions &options)
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace)
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate)
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate)
 
::ros::NodeHandle getDefaultDiagNh (const ::ros::NodeHandle &pubSubNh, const ::std::string &diagNamespace)
 
::cras::BoundParamHelperPtr getDiagParams (const ::ros::NodeHandle &nh, const ::std::string &diagNamespace, const ::std::string &topic)
 
::cras::DiagnosticUpdatergetDiagUpdater (bool forceNew=false) const
 
void startDiagTimer () const
 
void startDiagTimer (const ::ros::NodeHandle &nh) const
 
void stopDiagTimer () const
 
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
 
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 
- Protected Member Functions inherited from cras::TimeJumpResettable
void checkTimeJump ()
 
virtual void checkTimeJump (const ::ros::Time &now)
 
void initRos (const ::ros::NodeHandle &pnh) override
 
void startAutoCheckTimeJump ()
 
virtual void startAutoCheckTimeJump (const ::ros::WallRate &rate)
 
virtual void stopAutoCheckTimeJump ()
 
 TimeJumpResettable (const ::cras::LogHelperPtr &log)
 
 ~TimeJumpResettable () override
 
- Protected Member Functions inherited from cras::Resettable
 Resettable (const ::cras::LogHelperPtr &log)
 
virtual ~Resettable ()
 
- Protected Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet >
void updateThreadName () const
 
- Protected Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet >
inline ::std::string getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
ResultType getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::std::string getParam (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
ResultType getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
::cras::BoundParamHelperPtr params (const ::ros::NodeHandle &node, const ::std::string &ns="") const
 
::cras::BoundParamHelperPtr paramsForNodeHandle (const ::ros::NodeHandle &node) const
 
::cras::BoundParamHelperPtr privateParams (const ::std::string &ns="") const
 
::cras::BoundParamHelperPtr publicParams (const ::std::string &ns="") const
 

Protected Attributes

::ros::Publisher activePriorityPub
 Publisher for active priority. More...
 
::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter > > beforeDisableMessages
 The messages to be injected into the mux right before a topic is disabled. More...
 
::std::unordered_set<::std::string > beforeDisableMessagesWithHeader
 Cached list of "before disable" messages that have a Header. More...
 
::cras::optional< intlastActivePriority
 The active priority after the last publishChanges() call. More...
 
::std::unordered_map<::std::string, ::std::string > lastSelectedTopics
 The selected output topics after the last publishChanges() call. More...
 
::std::unordered_map<::std::string, ::cras::priority_mux::LockConfiglockConfigs
 Configurations of lock topics. More...
 
::std::unique_ptr<::cras::PriorityMuxmux
 Mux instance. More...
 
std::unordered_map< std::string, ::cras::priority_mux::OutputTopicConfigoutTopicConfigs
 Configurations of output topics. More...
 
::std::unordered_set<::std::string > outTopics
 All output topic names. More...
 
::std::unordered_map<::std::string, ::ros::Publisherpublishers
 Map of output topic and the associated publisher. More...
 
size_t queueSize {10u}
 Queue size of all publishers and subscribers. More...
 
::ros::Subscriber resetSub
 Subscriber for reset topic. More...
 
::std::unordered_map<::std::string, ::ros::PublisherselectedPublishers
 Map of publishers of the topics announcing currently selected publishers. More...
 
::std::list<::ros::Subscribersubscribers
 List of subscribers. Just for keeping them alive. More...
 
bool tcpNoDelay {false}
 Whether tcpNoDelay() flag should be set for all subscribers. More...
 
::std::unordered_map<::std::string, ::ros::Timertimers
 Map of timer names and the timers. More...
 
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfigtopicConfigs
 Configurations of input topics. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 
- Protected Attributes inherited from cras::InterruptibleSleepInterface
::ros::WallDuration pollDuration
 

Additional Inherited Members

- Public Member Functions inherited from cras::Nodelet
 ~Nodelet () override=default
 
- Public Member Functions inherited from NodeletBase<::nodelet::Nodelet >
 ~NodeletBase () override=default
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
- Public Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet >
 NodeletWithDiagnostics ()
 
virtual ~NodeletWithDiagnostics ()
 
- Public Member Functions inherited from NodeletWithSharedTfBuffer< ::nodelet::Nodelet >
::cras::NodeletAwareTFBuffergetBuffer () const override
 
 NodeletWithSharedTfBuffer ()
 
void setBuffer (const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override
 
bool usesSharedBuffer () const override
 
virtual ~NodeletWithSharedTfBuffer ()
 
- Public Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet >
 ~ThreadNameUpdatingNodelet () override
 
- Public Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet >
 NodeletParamHelper ()
 
 ~NodeletParamHelper () override
 
- Public Member Functions inherited from cras::ParamHelper
::cras::LogHelperPtr getLogger () const
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
 ParamHelper (const ::cras::LogHelperPtr &log)
 
void setLogger (const ::cras::LogHelperPtr &logger)
 
virtual ~ParamHelper ()=default
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 
- Public Member Functions inherited from StatefulNodelet< ::nodelet::Nodelet >
bool ok () const override
 
void requestStop () override
 
void shutdown ()
 
virtual ~StatefulNodelet ()
 
- Public Member Functions inherited from cras::InterruptibleSleepInterface
 InterruptibleSleepInterface ()
 
virtual bool sleep (const ::ros::Duration &duration) const
 
virtual ~InterruptibleSleepInterface ()
 

Detailed Description

Priority-based muxer nodelet for topics.

It guards access to one or more output topics for which there are several input topics fighting. To determine which input topic "wins" its desired output access, priorities are assigned to each input topic, and each input topic specifies a validity period for which it is considered. This validity period should be renewed every time a message is received on the topic. This means that when messages stop coming for a topic, its priority is given up. Each input topic can also be explicitly released.

When more output topics are specified, the priority is still shared. This means that receiving a high-priority message for one output topic also sets all other output topics to this higher priority. This effectively allows e.g. managing access to robot motors in case there are several topics that can control them via different approaches.

The mux can also process binary lock messages. There are two types of them: permanent and time-based. Both act via locking their assigned priority, which means no messages with lower priorities will qualify to get to their output topics. Permanent locks just lock or unlock their priority. Time-based lock messages are expected to come regularly and when they stop coming for some time, their priority is locked. They can also carry explicit locking commands.

ROS parameters:

Subscribed topics:

Published topics:

Definition at line 113 of file priority_mux.h.

Member Function Documentation

◆ cb()

void cras::PriorityMuxNodelet::cb ( const ::std::string &  inTopic,
const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &  event 
)
protectedvirtual

Callback method triggered when a message is received on the input topic.

Parameters
[in]inTopicThe topic the message was received on.
[in]eventThe received message ShapeShifter.

Definition at line 376 of file priority_mux.cpp.

◆ disableCb()

void cras::PriorityMuxNodelet::disableCb ( const ::std::string &  inTopic,
const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &  event 
)
protectedvirtual

Callback method triggered when a disable message is received.

Parameters
[in]inTopicThe input topic for which the disable message was received on.
[in]eventThe received message ShapeShifter. If the message is of std_msgs::Bool type, it gets special handling (the data field of the message tells whether the topic should be disabled or enabled).

Definition at line 444 of file priority_mux.cpp.

◆ lockCb()

void cras::PriorityMuxNodelet::lockCb ( const ::std::string &  topic,
const ::ros::MessageEvent<::std_msgs::Bool const > &  event 
)
protectedvirtual

Callback method triggered when a lock message is received.

Parameters
[in]topicThe topic the lock message was received on.
[in]eventThe received lock message.

Definition at line 437 of file priority_mux.cpp.

◆ onInit()

void cras::PriorityMuxNodelet::onInit ( )
overrideprotectedvirtual

Reimplemented from NodeletBase<::nodelet::Nodelet >.

Definition at line 36 of file priority_mux.cpp.

◆ onTimeout()

void cras::PriorityMuxNodelet::onTimeout ( const ::std::string &  name,
const ::ros::TimerEvent  
)
protected

Method triggered on timer timeout. This should update the mux and check for changes.

Parameters
[in]nameThe name of the timer.
[in]eventThe timer event.

Definition at line 518 of file priority_mux.cpp.

◆ publishChanges()

void cras::PriorityMuxNodelet::publishChanges ( )
protected

Check what changed from the last publishChanges() call and if there are changes, publish them (active priority, selected output topics etc.).

Definition at line 489 of file priority_mux.cpp.

◆ reset()

void cras::PriorityMuxNodelet::reset ( )
protectedvirtual

Reset the mux to its initial state.

Reimplemented from NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.

Definition at line 538 of file priority_mux.cpp.

◆ resetCb()

void cras::PriorityMuxNodelet::resetCb ( const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &  event)
protectedvirtual

Callback method triggered when a reset message is received.

Parameters
[in]eventThe received message ShapeShifter. It can be anything, this method is only interested in the fact that some message was received.

Definition at line 553 of file priority_mux.cpp.

◆ setTimer()

void cras::PriorityMuxNodelet::setTimer ( const ::std::string &  name,
const ::ros::Duration timeout 
)
protected

Set a timer that will call onTimeout() after the specified time.

Parameters
[in]nameThe name of the timer.
[in]timeoutThe duration of the timer.

Definition at line 525 of file priority_mux.cpp.

Member Data Documentation

◆ activePriorityPub

::ros::Publisher cras::PriorityMuxNodelet::activePriorityPub
protected

Publisher for active priority.

Definition at line 183 of file priority_mux.h.

◆ beforeDisableMessages

::std::unordered_map<::std::string, ::ros::MessageEvent<::cras::ShapeShifter> > cras::PriorityMuxNodelet::beforeDisableMessages
protected

The messages to be injected into the mux right before a topic is disabled.

Definition at line 213 of file priority_mux.h.

◆ beforeDisableMessagesWithHeader

::std::unordered_set<::std::string> cras::PriorityMuxNodelet::beforeDisableMessagesWithHeader
protected

Cached list of "before disable" messages that have a Header.

Definition at line 216 of file priority_mux.h.

◆ lastActivePriority

::cras::optional<int> cras::PriorityMuxNodelet::lastActivePriority
protected

The active priority after the last publishChanges() call.

Definition at line 207 of file priority_mux.h.

◆ lastSelectedTopics

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

The selected output topics after the last publishChanges() call.

Definition at line 210 of file priority_mux.h.

◆ lockConfigs

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

Configurations of lock topics.

Definition at line 198 of file priority_mux.h.

◆ mux

::std::unique_ptr<::cras::PriorityMux> cras::PriorityMuxNodelet::mux
protected

Mux instance.

Definition at line 174 of file priority_mux.h.

◆ outTopicConfigs

std::unordered_map<std::string, ::cras::priority_mux::OutputTopicConfig> cras::PriorityMuxNodelet::outTopicConfigs
protected

Configurations of output topics.

Definition at line 201 of file priority_mux.h.

◆ outTopics

::std::unordered_set<::std::string> cras::PriorityMuxNodelet::outTopics
protected

All output topic names.

Definition at line 204 of file priority_mux.h.

◆ publishers

::std::unordered_map<::std::string, ::ros::Publisher> cras::PriorityMuxNodelet::publishers
protected

Map of output topic and the associated publisher.

Definition at line 180 of file priority_mux.h.

◆ queueSize

size_t cras::PriorityMuxNodelet::queueSize {10u}
protected

Queue size of all publishers and subscribers.

Definition at line 219 of file priority_mux.h.

◆ resetSub

::ros::Subscriber cras::PriorityMuxNodelet::resetSub
protected

Subscriber for reset topic.

Definition at line 189 of file priority_mux.h.

◆ selectedPublishers

::std::unordered_map<::std::string, ::ros::Publisher> cras::PriorityMuxNodelet::selectedPublishers
protected

Map of publishers of the topics announcing currently selected publishers.

Definition at line 186 of file priority_mux.h.

◆ subscribers

::std::list<::ros::Subscriber> cras::PriorityMuxNodelet::subscribers
protected

List of subscribers. Just for keeping them alive.

Definition at line 177 of file priority_mux.h.

◆ tcpNoDelay

bool cras::PriorityMuxNodelet::tcpNoDelay {false}
protected

Whether tcpNoDelay() flag should be set for all subscribers.

Definition at line 222 of file priority_mux.h.

◆ timers

::std::unordered_map<::std::string, ::ros::Timer> cras::PriorityMuxNodelet::timers
protected

Map of timer names and the timers.

Definition at line 192 of file priority_mux.h.

◆ topicConfigs

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

Configurations of input topics.

Definition at line 195 of file priority_mux.h.


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


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Mar 2 2024 03:47:49