Priority-based muxer nodelet for topics. More...
#include <priority_mux.h>
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, bool invert, 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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () 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 ¶mNamespace) |
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, const ::ros::Rate &defaultRate) |
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, 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::DiagnosticUpdater & | getDiagUpdater (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< int > | lastActivePriority |
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::LockConfig > | lockConfigs |
Configurations of lock topics. More... | |
::std::unique_ptr<::cras::PriorityMux > | mux |
Mux instance. More... | |
std::unordered_map< std::string, ::cras::priority_mux::OutputTopicConfig > | outTopicConfigs |
Configurations of output topics. More... | |
::std::unordered_set<::std::string > | outTopics |
All output topic names. More... | |
::std::unordered_map<::std::string, ::ros::Publisher > | publishers |
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::Publisher > | selectedPublishers |
Map of publishers of the topics announcing currently selected publishers. More... | |
::std::list<::ros::Subscriber > | subscribers |
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::Timer > | timers |
Map of timer names and the timers. More... | |
::std::unordered_map<::std::string, ::cras::priority_mux::TopicConfig > | topicConfigs |
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::NodeletAwareTFBuffer & | getBuffer () 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 ¶m, 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 ¶m, 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 ¶m, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const |
ResultType | getParam (const ::cras::GetParamAdapter ¶m, 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 ¶m, 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 ¶m, 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 ¶m, 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 ¶m, 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 () |
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:
~queue_size
(uint, default 10): Queue size for all subscribers and publishers.~tcp_no_delay
(bool, default False): If True, the TCP_NODELAY
flag is set for all subscribers. This should decrease the latency of small messages, but might give suboptimal transmission speed for large messages.~default_out_topic
(str, default "mux_out"): Default output topic to use when none is explicitly specified for a topic configuration.~none_topic
(str, default "__none"): Virtual name of a topic reported as selected when no priority is active.~none_priority
(int, default 0): Priority level signalling that no priority is active.~subscriber_connect_delay
(double, default 0.1 s): Time to wait before a newly created non-latched output topic publisher will publish its first message.~topics
(list or dict): Definition of subscribed topics and their priorities. If dict, only values are used.topic
(str): The input topic to subscribe.priority
(int): Priority of the input topic.out_topic
(str, default default_out_topic
): The topic to which the input should be relayed if its priority is active.timeout
(double): How long does a message on this topic hold its priority.name
(str, default topic
): Human-readable description of the input topic.disable_topic
(str, default ""): If nonempty, this topic will be subscribed to allow disabling the input topic.disable_topic_inverted
(bool, default false): If true, topic
will get disabled when false is received on disable_topic
. If false, topic
will get disabled when true is received on disable_topic
. In case disable_topic
is not of std_msgs/Bool
type, this parameter does nothing.before_disable_message
(str, optional): If set, this string should point to a bagfile containing a single message. This message will be published on this topic just before the topic becomes disabled.queue_size
(uint, default ~queue_size
): Queue size for the subscriber.~locks
(list or dict): Definition of lock topics and their priorities. If dict, only values are used.topic
(str): The lock topic to subscribe.priority
(int): Priority of the lock topic.timeout
(double): If zero, the lock only uses data in the sent Bool messages to determine whether it is locked or not. If non-zero, the lock will get locked when the last message on the lock topic is older than the timeout.name
(str, default topic
): Human-readable description of the lock topic.~out_topics
(list or dict): Optional configuration of output topics. If dict, only values are used.topic
(str): The output topic.force_latch
(bool, optional): If set, forces the topic's latching status to the value. Otherwise, latching is configured based on latching of the first received message.subscriber_connect_delay
(double, default ~subscriber_connect_delay
): Time to wait before publishing the first message after the publisher is created. Only applies to non-latched topics.num_subscribers_to_wait
(uint, default 0): If non-zero, when the publisher is created, it will wait until it has this number of subscribers before it publishes its first message. This is more reliable than setting the delay if you know the number of subscribers. The number is not the actual number of subscriber objects, but rather the number of subscribing separate nodes (so e.g. all subscriptions from a single nodelet manager count as one).queue_size
(uint, default ~queue_size
): Queue size for the publisher.Subscribed topics:
~topics/topic
(any type): Input messages.~topics/disable_topic
(any type): Disable messages. If the topic type is std_msgs/Bool
, the associated input topic is enabled/disabled according to the value of the message (true means disable). If the topic is of any other type, receiving a message on this topic disables the associated input topic for the timeout
specified for the input topic.~locks/topic
(std_msgs/Bool
): Lock messages.~reset
(any type): When a message is received on this topic, the mux is reset.Published topics:
~topics/out_topic
(any type): The muxed output messages.~active_priority
(std_msgs/Int32
): The currently active priority.~selected/${out_topic}
(std_msgs/String
): For each output topic, this topic tells which input is currently relayed to the output. Definition at line 117 of file priority_mux.h.
|
protectedvirtual |
Callback method triggered when a message is received on the input topic.
[in] | inTopic | The topic the message was received on. |
[in] | event | The received message ShapeShifter. |
Definition at line 384 of file priority_mux.cpp.
|
protectedvirtual |
Callback method triggered when a disable message is received.
[in] | inTopic | The input topic for which the disable message was received on. |
[in] | invert | If true, the topic will get disabled when false is received on the disable topic. If false, the topic will get disabled when true is received on the disable topic. In case the disable topic is not of std_msgs/Bool type, this parameter does nothing. |
[in] | event | The 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 452 of file priority_mux.cpp.
|
protectedvirtual |
Callback method triggered when a lock message is received.
[in] | topic | The topic the lock message was received on. |
[in] | event | The received lock message. |
Definition at line 445 of file priority_mux.cpp.
|
overrideprotectedvirtual |
Reimplemented from NodeletBase<::nodelet::Nodelet >.
Definition at line 37 of file priority_mux.cpp.
|
protected |
Method triggered on timer timeout. This should update the mux and check for changes.
[in] | name | The name of the timer. |
[in] | event | The timer event. |
Definition at line 530 of file priority_mux.cpp.
|
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 501 of file priority_mux.cpp.
|
protectedvirtual |
Reset the mux to its initial state.
Reimplemented from NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.
Definition at line 550 of file priority_mux.cpp.
|
protectedvirtual |
Callback method triggered when a reset message is received.
[in] | event | The received message ShapeShifter. It can be anything, this method is only interested in the fact that some message was received. |
Definition at line 565 of file priority_mux.cpp.
|
protected |
Set a timer that will call onTimeout()
after the specified time.
[in] | name | The name of the timer. |
[in] | timeout | The duration of the timer. |
Definition at line 537 of file priority_mux.cpp.
|
protected |
Publisher for active priority.
Definition at line 191 of file priority_mux.h.
|
protected |
The messages to be injected into the mux right before a topic is disabled.
Definition at line 221 of file priority_mux.h.
|
protected |
Cached list of "before disable" messages that have a Header.
Definition at line 224 of file priority_mux.h.
|
protected |
The active priority after the last publishChanges()
call.
Definition at line 215 of file priority_mux.h.
|
protected |
The selected output topics after the last publishChanges()
call.
Definition at line 218 of file priority_mux.h.
|
protected |
Configurations of lock topics.
Definition at line 206 of file priority_mux.h.
|
protected |
Mux instance.
Definition at line 182 of file priority_mux.h.
|
protected |
Configurations of output topics.
Definition at line 209 of file priority_mux.h.
|
protected |
All output topic names.
Definition at line 212 of file priority_mux.h.
|
protected |
Map of output topic and the associated publisher.
Definition at line 188 of file priority_mux.h.
|
protected |
Queue size of all publishers and subscribers.
Definition at line 227 of file priority_mux.h.
|
protected |
Subscriber for reset topic.
Definition at line 197 of file priority_mux.h.
|
protected |
Map of publishers of the topics announcing currently selected publishers.
Definition at line 194 of file priority_mux.h.
|
protected |
List of subscribers. Just for keeping them alive.
Definition at line 185 of file priority_mux.h.
|
protected |
Whether tcpNoDelay()
flag should be set for all subscribers.
Definition at line 230 of file priority_mux.h.
|
protected |
Map of timer names and the timers.
Definition at line 200 of file priority_mux.h.
|
protected |
Configurations of input topics.
Definition at line 203 of file priority_mux.h.