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

Nodelet for throttling messages on a topic. More...

#include <throttle_messages.h>

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

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 ()
 Reset the rate limiter, e.g. after a time jump. 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

::std::unique_ptr<::cras::RateLimiterlimiter
 The rate limiter used for limiting output rate. More...
 
::std::mutex limiterMutex
 Mutex for working with the limiter. More...
 
::std::unique_ptr<::cras::GenericLazyPubSubpubSub
 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::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

Nodelet for throttling messages on a topic.

ROS parameters:

Subscribed topics:

Published topics:

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.

Definition at line 78 of file throttle_messages.h.

Member Function Documentation

◆ onInit()

void cras::ThrottleMessagesNodelet::onInit ( )
overrideprotectedvirtual

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

Definition at line 37 of file throttle_messages.cpp.

◆ onReset()

void cras::ThrottleMessagesNodelet::onReset ( const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &  )
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.

◆ processMessage()

void cras::ThrottleMessagesNodelet::processMessage ( const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &  event,
::ros::Publisher pub 
)
protected

Publish the incoming message if the rate limiter allows.

Parameters
[in]eventThe incoming message event.
[in]pubThe publisher to be used for publishing the throttled messages.
Note
It is safe to call this function from multiple threads (access to the rate limiter is mutex-protected).

Definition at line 117 of file throttle_messages.cpp.

◆ reset()

void cras::ThrottleMessagesNodelet::reset ( )
protectedvirtual

Reset the rate limiter, e.g. after a time jump.

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

Definition at line 111 of file throttle_messages.cpp.

Member Data Documentation

◆ limiter

::std::unique_ptr<::cras::RateLimiter> cras::ThrottleMessagesNodelet::limiter
protected

The rate limiter used for limiting output rate.

Definition at line 109 of file throttle_messages.h.

◆ limiterMutex

::std::mutex cras::ThrottleMessagesNodelet::limiterMutex
protected

Mutex for working with the limiter.

Definition at line 112 of file throttle_messages.h.

◆ pubSub

::std::unique_ptr<::cras::GenericLazyPubSub> cras::ThrottleMessagesNodelet::pubSub
protected

The lazy pair of subscriber and publisher.

Definition at line 82 of file throttle_messages.h.

◆ resetSub

::ros::Subscriber cras::ThrottleMessagesNodelet::resetSub
protected

Subscriber to the reset topic.

Definition at line 85 of file throttle_messages.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