Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_topic_tools::MUX Class Reference

#include <mux_nodelet.h>

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

Public Types

typedef ros::MessageEvent< topic_tools::ShapeShifterShapeShifterEvent
 

Public Member Functions

virtual bool addTopicCallback (topic_tools::MuxAdd::Request &req, topic_tools::MuxAdd::Response &res)
 
virtual bool deleteTopicCallback (topic_tools::MuxDelete::Request &req, topic_tools::MuxDelete::Response &res)
 
virtual void inputCallback (const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
 
virtual bool listTopicCallback (topic_tools::MuxList::Request &req, topic_tools::MuxList::Response &res)
 
virtual void onInit ()
 
virtual bool selectTopicCallback (topic_tools::MuxSelect::Request &req, topic_tools::MuxSelect::Response &res)
 
- 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 ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual void connectCb (const ros::SingleSubscriberPublisher &pub)
 
virtual void subscribeSelectedTopic ()
 
- 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 Attributes

bool advertised_
 
ros::NodeHandle pnh_
 
ros::Publisher pub_
 
ros::Publisher pub_selected_
 
std::string selected_topic_
 
ros::ServiceServer ss_add_
 
ros::ServiceServer ss_del_
 
ros::ServiceServer ss_list_
 
ros::ServiceServer ss_select_
 
boost::shared_ptr< ros::Subscribersub_
 
bool subscribing_
 
ros::TransportHints th_
 
std::vector< std::string > topics_
 

Detailed Description

Definition at line 48 of file mux_nodelet.h.

Member Typedef Documentation

Definition at line 51 of file mux_nodelet.h.

Member Function Documentation

bool jsk_topic_tools::MUX::addTopicCallback ( topic_tools::MuxAdd::Request &  req,
topic_tools::MuxAdd::Response &  res 
)
virtual

Definition at line 119 of file mux_nodelet.cpp.

void jsk_topic_tools::MUX::connectCb ( const ros::SingleSubscriberPublisher pub)
protectedvirtual

Definition at line 68 of file mux_nodelet.cpp.

bool jsk_topic_tools::MUX::deleteTopicCallback ( topic_tools::MuxDelete::Request &  req,
topic_tools::MuxDelete::Response &  res 
)
virtual

Definition at line 144 of file mux_nodelet.cpp.

void jsk_topic_tools::MUX::inputCallback ( const boost::shared_ptr< topic_tools::ShapeShifter const > &  msg)
virtual

Definition at line 193 of file mux_nodelet.cpp.

bool jsk_topic_tools::MUX::listTopicCallback ( topic_tools::MuxList::Request &  req,
topic_tools::MuxList::Response &  res 
)
virtual

Definition at line 164 of file mux_nodelet.cpp.

void jsk_topic_tools::MUX::onInit ( )
virtual

Implements nodelet::Nodelet.

Definition at line 44 of file mux_nodelet.cpp.

bool jsk_topic_tools::MUX::selectTopicCallback ( topic_tools::MuxSelect::Request &  req,
topic_tools::MuxSelect::Response &  res 
)
virtual

Definition at line 93 of file mux_nodelet.cpp.

void jsk_topic_tools::MUX::subscribeSelectedTopic ( )
protectedvirtual

Definition at line 173 of file mux_nodelet.cpp.

Member Data Documentation

bool jsk_topic_tools::MUX::advertised_
protected

Definition at line 65 of file mux_nodelet.h.

ros::NodeHandle jsk_topic_tools::MUX::pnh_
protected

Definition at line 72 of file mux_nodelet.h.

ros::Publisher jsk_topic_tools::MUX::pub_
protected

Definition at line 71 of file mux_nodelet.h.

ros::Publisher jsk_topic_tools::MUX::pub_selected_
protected

Definition at line 70 of file mux_nodelet.h.

std::string jsk_topic_tools::MUX::selected_topic_
protected

Definition at line 68 of file mux_nodelet.h.

ros::ServiceServer jsk_topic_tools::MUX::ss_add_
protected

Definition at line 74 of file mux_nodelet.h.

ros::ServiceServer jsk_topic_tools::MUX::ss_del_
protected

Definition at line 74 of file mux_nodelet.h.

ros::ServiceServer jsk_topic_tools::MUX::ss_list_
protected

Definition at line 74 of file mux_nodelet.h.

ros::ServiceServer jsk_topic_tools::MUX::ss_select_
protected

Definition at line 74 of file mux_nodelet.h.

boost::shared_ptr<ros::Subscriber> jsk_topic_tools::MUX::sub_
protected

Definition at line 69 of file mux_nodelet.h.

bool jsk_topic_tools::MUX::subscribing_
protected

Definition at line 66 of file mux_nodelet.h.

ros::TransportHints jsk_topic_tools::MUX::th_
protected

Definition at line 73 of file mux_nodelet.h.

std::vector<std::string> jsk_topic_tools::MUX::topics_
protected

Definition at line 67 of file mux_nodelet.h.


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


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19