Nodelet for throttling messages on a topic. More...
#include <throttle_messages.h>
Protected Member Functions | |
void | onInit () override |
virtual void | onReset (const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &) |
Called when the rate limiter should be reset. The incoming message can be of any type and should not be examined. More... | |
void | processMessage (const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub) |
Publish the incoming message if the rate limiter allows. More... | |
void | reset () override |
Reset the rate limiter, e.g. after a time jump. 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 | |
::std::unique_ptr<::cras::RateLimiter > | limiter |
The rate limiter used for limiting output rate. More... | |
::std::mutex | limiterMutex |
Mutex for working with the limiter. More... | |
::std::unique_ptr<::cras::GenericLazyPubSub > | pubSub |
The lazy pair of subscriber and publisher. More... | |
::ros::Subscriber | resetSub |
Subscriber to the reset topic. 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 |
::std::shared_ptr<::cras::NodeletAwareTFBuffer > | getBufferPtr () const |
NodeletWithSharedTfBuffer () | |
void | setBuffer (const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override |
bool | usesSharedBuffer () const override |
~NodeletWithSharedTfBuffer () override | |
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 () |
Nodelet for throttling messages on a topic.
ROS parameters:
~in_queue_size
(uint, default 10): Queue size for the subscriber.~out_queue_size
(uint, default $in_queue_size): Queue size for the publisher.~frequency
(Hz, positive double, default 1.0): The maximum rate of the published messages.~lazy
(bool, default False): Whether to shut down the subscriber when the publisher has no subscribers. The ~input
topic will be subscribed in the beginning, and will unsubscribe automatically after the first message is received (this is needed to determine the full type of the topic to publish).~tcp_no_delay
(bool, default False): If True, the TCP_NODELAY
flag is set for the subscriber. This should decrease the latency of small messages, but might give suboptimal transmission speed for large messages.~method
(enum, default TOKEN_BUCKET): The rate-limiting method.TOKEN_BUCKET
: more precise algorithm.~bucket_capacity
(uint, default 2): Maximum burst size in case the incoming messages stop for a while and then start coming again.~initial_tokens
(uint, default 1): How many messages can be published right after the nodelet is started or reset. If you set it to 0, the first message can be published after 1/frequency seconds.THROTTLE
: the algorithm from topic_tools/throttle. It is not very precise.Subscribed topics:
~input
(any type): The input messages. If lazy
is true, it will only be subscribed when ~output
has some subscribers.~reset
(any type): When a message is received on this topic, the rate limiter is reset into its initial state (i.e. token bucket will set the number of tokens to initial_tokens
). This should happen every time the ROS time jumps, e.g. when simulation is reset or a bag file starts playing again. The rate limiter should, however, reset itself when it notices a large jump backward in ROS time. Forward jumps are not autocorrected and require publishing a message on this topic.Published topics:
~output
(same type as ~input
): The throttled output messages.Command-line arguments: This nodelet (or node) can also be called in a way backwards compatible with topic_tools/throttle. This means you can pass CLI arguments specifying the topics to subscribe/publish and the rate.
rosrun cras_topic_tools throttle messages TOPIC_IN RATE [TOPIC_OUT]
messages
is just a static word and is there for compatibility with topic_tools/relay. It has to be there if you configure this node(let) via CLI.TOPIC_IN
: The topic to subscribe. It is resolved against parent namespace of the node(let) (as opposed to the ~input
topic which is resolved against the private node(let) namespace).RATE
: The output rate. If both this argument and ~frequency
parameter are specified, the ROS parameter wins.TOPIC_OUT
: The topic to publish. It is resolved against parent namespace of the node(let) (as opposed to the ~output
topic which is resolved against the private node(let) namespace). If not specified, output topic will be ${TOPIC_IN}_throttle
. Definition at line 78 of file throttle_messages.h.
|
overrideprotectedvirtual |
Reimplemented from NodeletBase<::nodelet::Nodelet >.
Definition at line 37 of file throttle_messages.cpp.
|
protectedvirtual |
Called when the rate limiter should be reset. The incoming message can be of any type and should not be examined.
Definition at line 106 of file throttle_messages.cpp.
|
protected |
Publish the incoming message if the rate limiter allows.
[in] | event | The incoming message event. |
[in] | pub | The publisher to be used for publishing the throttled messages. |
Definition at line 118 of file throttle_messages.cpp.
|
overrideprotectedvirtual |
Reset the rate limiter, e.g. after a time jump.
Reimplemented from NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.
Definition at line 111 of file throttle_messages.cpp.
|
protected |
The rate limiter used for limiting output rate.
Definition at line 109 of file throttle_messages.h.
|
protected |
Mutex for working with the limiter.
Definition at line 112 of file throttle_messages.h.
|
protected |
The lazy pair of subscriber and publisher.
Definition at line 82 of file throttle_messages.h.
|
protected |
Subscriber to the reset topic.
Definition at line 85 of file throttle_messages.h.