|
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 () override |
| Reset the repeater, e.g. after a time jump. More...
|
|
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 |
|
::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={}) |
|
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 |
|
| Resettable (const ::cras::LogHelperPtr &log) |
|
virtual | ~Resettable () |
|
void | updateThreadName () const |
|
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 |
|
|
| ~Nodelet () override=default |
|
| ~NodeletBase () override=default |
|
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 () |
|
| NodeletWithDiagnostics () |
|
virtual | ~NodeletWithDiagnostics () |
|
::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 |
|
| ~ThreadNameUpdatingNodelet () override |
|
| NodeletParamHelper () |
|
| ~NodeletParamHelper () override |
|
::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 |
|
::cras::LogHelperConstPtr | getCrasLogger () const |
|
| HasLogger (const ::cras::LogHelperPtr &log) |
|
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
|
bool | ok () const override |
|
void | requestStop () override |
|
void | shutdown () |
|
virtual | ~StatefulNodelet () |
|
| InterruptibleSleepInterface () |
|
virtual bool | sleep (const ::ros::Duration &duration) const |
|
virtual | ~InterruptibleSleepInterface () |
|
Nodelet for repeating messages coming at a slower rate (or even just a single message).
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.
~rate
(Hz, positive double, default 1.0): The desired 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). This can have unexpected consequences as the nodelet doesn't listen for new messages that came in when the publisher had no subscribers. So when the nodelet should start publishing again, it will repeat the last message it received before unsubscribing.
~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.
~max_age
(double, no default): If set, this parameter instructs the repeater to check how old the re-published message would be. If it is older than ros::Time::now() - max_age
, it will no longer be published. This setting requires that the type of the message contains a Header field at the beginning. Setting it on header-less topics can cause unexpected behavior and random rejection of messages.
~max_repeats
(uint, no default): If set, this parameter tells how many times a single message can be repeated.
~discard_older_messages
(bool, default false): If true, incoming messages' time stamp will be compared to the last stored message, and if the incoming message is older than the stored one, it will be discarded. This setting requires that the type of the message contains a Header field at the beginning. Setting it on header-less topics can cause unexpected behavior and random rejection of messages.
~reset_on_msg
(bool, default true): Whether the internal repeating timer should be reset to count from 0 when an incoming message is stored.
~publish_only_on_timer
(bool, default false): If true, messages are only published on timer events. If false, they are also published right away as they come on the input topic.
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 repeater is reset into its initial state (i.e. the last received message is discarded). This should happen every time the ROS time jumps, e.g. when simulation is reset or a bag file starts playing again.
Published topics:
~output
(same type as ~input
): The output messages.
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.
rosrun cras_topic_tools repeat TOPIC_IN RATE [TOPIC_OUT]
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 ~rate
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}_repeat
.
- 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.