Public Types | Protected Member Functions | Protected Attributes
jsk_topic_tools::Passthrough Class Reference

#include <passthrough_nodelet.h>

Inheritance diagram for jsk_topic_tools::Passthrough:
Inheritance graph
[legend]

List of all members.

Public Types

typedef ros::MessageEvent
< topic_tools::ShapeShifter
ShapeShifterEvent

Protected Member Functions

virtual ros::Publisher advertise (boost::shared_ptr< topic_tools::ShapeShifter const > msg, const std::string &topic)
 Advertise a topic according to a specific message instance.
virtual void connectCb ()
virtual void disconnectCb ()
virtual void inputCallback (const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
 Callback function for ~input. It advertise ~output topic according to the definition of input topic at the first time. After that, Passthrough relays ~input topic to ~output topic until end_time_.
virtual void onInit ()
 Initialization function.
virtual bool requestCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 Callback function for ~request service.
virtual bool requestDurationCallback (jsk_topic_tools::PassthroughDuration::Request &req, jsk_topic_tools::PassthroughDuration::Response &res)
 Callback function for ~request_duration service.
virtual void requestDurationCallbackImpl (const ros::Duration &duration)
 Implementation of requestDurationCallback.
virtual bool stopCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 Callback function of ~stop service. Force to stop publishing messages.

Protected Attributes

bool advertised_
double default_duration_
ros::Time end_time_
ros::Time finish_time_
boost::mutex mutex_
ros::NodeHandle pnh_
ros::Publisher pub_
bool publish_requested_
ros::ServiceServer request_duration_srv_
ros::ServiceServer request_srv_
ros::ServiceServer stop_srv_
ros::Subscriber sub_
bool subscribing_

Detailed Description

Definition at line 48 of file passthrough_nodelet.h.


Member Typedef Documentation

Definition at line 51 of file passthrough_nodelet.h.


Member Function Documentation

ros::Publisher jsk_topic_tools::Passthrough::advertise ( boost::shared_ptr< topic_tools::ShapeShifter const >  msg,
const std::string &  topic 
) [protected, virtual]

Advertise a topic according to a specific message instance.

Definition at line 194 of file passthrough_nodelet.cpp.

void jsk_topic_tools::Passthrough::connectCb ( ) [protected, virtual]

Definition at line 161 of file passthrough_nodelet.cpp.

void jsk_topic_tools::Passthrough::disconnectCb ( ) [protected, virtual]

Definition at line 178 of file passthrough_nodelet.cpp.

void jsk_topic_tools::Passthrough::inputCallback ( const boost::shared_ptr< topic_tools::ShapeShifter const > &  msg) [protected, virtual]

Callback function for ~input. It advertise ~output topic according to the definition of input topic at the first time. After that, Passthrough relays ~input topic to ~output topic until end_time_.

If ros::Time::now() goes over end_time_, publish_requested_ flag is set to false.

Definition at line 131 of file passthrough_nodelet.cpp.

void jsk_topic_tools::Passthrough::onInit ( ) [protected, virtual]

Initialization function.

Setup subscriber for ~input topic.

senario 1. 1-1 subscribe input 1-2 message 1-3 advertise output 1-4 unsubscribe input 1-5 prepare for request senario 2. 1-1 subscribe input 1-2 request 1-3 message 1-4 advertise 1-5 unsubscribe at the end of request

Implements nodelet::Nodelet.

Definition at line 53 of file passthrough_nodelet.cpp.

bool jsk_topic_tools::Passthrough::requestCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected, virtual]

Callback function for ~request service.

This callback reqtrieves std_srvs::Empty and enables passthrough for ~default_duration seconds.

Definition at line 123 of file passthrough_nodelet.cpp.

bool jsk_topic_tools::Passthrough::requestDurationCallback ( jsk_topic_tools::PassthroughDuration::Request &  req,
jsk_topic_tools::PassthroughDuration::Response &  res 
) [protected, virtual]

Callback function for ~request_duration service.

This callback reqtrieves jsk_topic_tools::PassThroughDuration and it has a duration to relay message. In side of this function, end_time_ is updated relative to ros::Time::now().

If duration is equivalent to ros::Duration(0), it is interpreted as eternal.

Definition at line 115 of file passthrough_nodelet.cpp.

void jsk_topic_tools::Passthrough::requestDurationCallbackImpl ( const ros::Duration duration) [protected, virtual]

Implementation of requestDurationCallback.

Definition at line 84 of file passthrough_nodelet.cpp.

bool jsk_topic_tools::Passthrough::stopCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected, virtual]

Callback function of ~stop service. Force to stop publishing messages.

Definition at line 71 of file passthrough_nodelet.cpp.


Member Data Documentation

Definition at line 126 of file passthrough_nodelet.h.

Definition at line 122 of file passthrough_nodelet.h.

Definition at line 129 of file passthrough_nodelet.h.

Definition at line 120 of file passthrough_nodelet.h.

boost::mutex jsk_topic_tools::Passthrough::mutex_ [protected]

Definition at line 123 of file passthrough_nodelet.h.

Definition at line 128 of file passthrough_nodelet.h.

Definition at line 124 of file passthrough_nodelet.h.

Definition at line 121 of file passthrough_nodelet.h.

Definition at line 130 of file passthrough_nodelet.h.

Definition at line 132 of file passthrough_nodelet.h.

Definition at line 131 of file passthrough_nodelet.h.

Definition at line 125 of file passthrough_nodelet.h.

Definition at line 127 of file passthrough_nodelet.h.


The documentation for this class was generated from the following files:


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56