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

Nodelet for repeating messages coming at a slower rate (or even just a single message). More...

#include <repeat.h>

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

Protected Member Functions

void everyPeriod (const ::ros::TimerEvent &)
 Timer callback. Publish the last stored message if it is eligible. More...
 
virtual bool inspectStamps () const
 Whether Header should be extracted from the message and its time stamp should undergo inspection. More...
 
virtual void maybePublish ()
 Publish the last stored message (if it is eligible). More...
 
void onInit () override
 
virtual void onReset (const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &)
 Called when the repeater 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)
 Record the incoming message if it passes validations, and publish it if publishOnlyOnTimer is false. More...
 
void reset ()
 Reset the repeater, 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

bool discardOlderMessages {false}
 Whether to discard an incoming message if its stamp is older than the previously accepted message. More...
 
::cras::optional< bool > hasHeader {::cras::nullopt}
 
::cras::optional<::ros::TimelastMsgStamp
 Time stamp of the last stored message (only filled if inspectStamps() returns true. More...
 
::cras::optional<::ros::DurationmaxAge {::cras::nullopt}
 Maximum age of a message to allow publishing it (the message has to have a Header). More...
 
::cras::optional< size_t > maxRepeats {::cras::nullopt}
 Maximum number of repetitions of a single message (only limited when set). More...
 
::topic_tools::ShapeShifter::ConstPtr msg
 The last stored message (null if no message has been received yet). More...
 
::std::mutex msgMutex
 Mutex protecting msg, lastMsgStamp and numRepeats. More...
 
size_t numRepeats {0}
 Number of times the last stored message has been repeated. More...
 
::ros::Publisher pub
 The publisher of the repeated messages. More...
 
bool publishOnlyOnTimer {false}
 Whether to publish only on timer events, or also when an incoming message is received. More...
 
::std::unique_ptr<::cras::GenericLazyPubSubpubSub
 The lazy pair of subscriber and publisher. More...
 
::std::unique_ptr<::ros::Raterate
 The desired output rate. More...
 
bool resetOnMsg {true}
 Whether to reset the publication timer when a new message arrives. More...
 
::ros::Subscriber resetSub
 Subscriber to the reset topic. More...
 
::ros::Timer timer
 The timer periodically republishing the last stored message. 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 repeating messages coming at a slower rate (or even just a single message).

ROS parameters:

Subscribed topics:

Published topics:

Command-line arguments: This nodelet (or node) can also be called with some arguments passed on command line. This means you can pass CLI arguments specifying the topics to subscribe/publish and the rate.

Note
If reset_on_msg and publish_only_on_timer are both true and the rate of the incoming messages is higher than rate parameter, no message will ever be published by this repeater (the timer will get reset earlier than it can ever fire).

Definition at line 94 of file repeat.h.

Member Function Documentation

◆ everyPeriod()

void cras::RepeatMessagesNodelet::everyPeriod ( const ::ros::TimerEvent )
protected

Timer callback. Publish the last stored message if it is eligible.

Definition at line 211 of file repeat.cpp.

◆ inspectStamps()

bool cras::RepeatMessagesNodelet::inspectStamps ( ) const
protectedvirtual

Whether Header should be extracted from the message and its time stamp should undergo inspection.

Returns
Whether to extract the stamp.

Definition at line 206 of file repeat.cpp.

◆ maybePublish()

void cras::RepeatMessagesNodelet::maybePublish ( )
protectedvirtual

Publish the last stored message (if it is eligible).

Definition at line 181 of file repeat.cpp.

◆ onInit()

void cras::RepeatMessagesNodelet::onInit ( )
overrideprotectedvirtual

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

Definition at line 38 of file repeat.cpp.

◆ onReset()

void cras::RepeatMessagesNodelet::onReset ( const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &  )
protectedvirtual

Called when the repeater should be reset. The incoming message can be of any type and should not be examined.

Definition at line 101 of file repeat.cpp.

◆ processMessage()

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

Record the incoming message if it passes validations, and publish it if publishOnlyOnTimer is false.

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

Definition at line 116 of file repeat.cpp.

◆ reset()

void cras::RepeatMessagesNodelet::reset ( )
protectedvirtual

Reset the repeater, e.g. after a time jump.

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

Definition at line 106 of file repeat.cpp.

Member Data Documentation

◆ discardOlderMessages

bool cras::RepeatMessagesNodelet::discardOlderMessages {false}
protected

Whether to discard an incoming message if its stamp is older than the previously accepted message.

Definition at line 150 of file repeat.h.

◆ hasHeader

::cras::optional<bool> cras::RepeatMessagesNodelet::hasHeader {::cras::nullopt}
protected

Definition at line 170 of file repeat.h.

◆ lastMsgStamp

::cras::optional<::ros::Time> cras::RepeatMessagesNodelet::lastMsgStamp
protected

Time stamp of the last stored message (only filled if inspectStamps() returns true.

Definition at line 165 of file repeat.h.

◆ maxAge

::cras::optional<::ros::Duration> cras::RepeatMessagesNodelet::maxAge {::cras::nullopt}
protected

Maximum age of a message to allow publishing it (the message has to have a Header).

Definition at line 147 of file repeat.h.

◆ maxRepeats

::cras::optional<size_t> cras::RepeatMessagesNodelet::maxRepeats {::cras::nullopt}
protected

Maximum number of repetitions of a single message (only limited when set).

Definition at line 144 of file repeat.h.

◆ msg

::topic_tools::ShapeShifter::ConstPtr cras::RepeatMessagesNodelet::msg
protected

The last stored message (null if no message has been received yet).

Definition at line 162 of file repeat.h.

◆ msgMutex

::std::mutex cras::RepeatMessagesNodelet::msgMutex
protected

Mutex protecting msg, lastMsgStamp and numRepeats.

Definition at line 159 of file repeat.h.

◆ numRepeats

size_t cras::RepeatMessagesNodelet::numRepeats {0}
protected

Number of times the last stored message has been repeated.

Definition at line 168 of file repeat.h.

◆ pub

::ros::Publisher cras::RepeatMessagesNodelet::pub
protected

The publisher of the repeated messages.

Definition at line 176 of file repeat.h.

◆ publishOnlyOnTimer

bool cras::RepeatMessagesNodelet::publishOnlyOnTimer {false}
protected

Whether to publish only on timer events, or also when an incoming message is received.

Definition at line 156 of file repeat.h.

◆ pubSub

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

The lazy pair of subscriber and publisher.

Definition at line 98 of file repeat.h.

◆ rate

::std::unique_ptr<::ros::Rate> cras::RepeatMessagesNodelet::rate
protected

The desired output rate.

Definition at line 141 of file repeat.h.

◆ resetOnMsg

bool cras::RepeatMessagesNodelet::resetOnMsg {true}
protected

Whether to reset the publication timer when a new message arrives.

Definition at line 153 of file repeat.h.

◆ resetSub

::ros::Subscriber cras::RepeatMessagesNodelet::resetSub
protected

Subscriber to the reset topic.

Definition at line 101 of file repeat.h.

◆ timer

::ros::Timer cras::RepeatMessagesNodelet::timer
protected

The timer periodically republishing the last stored message.

Definition at line 173 of file repeat.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