Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <pluginlib/class_list_macros.h>
00035 #include "jsk_topic_tools/relay_nodelet.h"
00036
00037 namespace jsk_topic_tools
00038 {
00039
00040 void Relay::onInit()
00041 {
00042 advertised_ = false;
00043 subscribing_ = false;
00044 pnh_ = getPrivateNodeHandle();
00045 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00046 &Relay::inputCallback, this, th_);
00047 }
00048
00049 void Relay::inputCallback(const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00050 {
00051 boost::mutex::scoped_lock lock(mutex_);
00052 if (!advertised_) {
00053
00054
00055
00056
00057 ros::SubscriberStatusCallback connect_cb
00058 = boost::bind( &Relay::connectCb, this);
00059 ros::SubscriberStatusCallback disconnect_cb
00060 = boost::bind( &Relay::disconnectCb, this);
00061 ros::AdvertiseOptions opts("output", 1,
00062 msg->getMD5Sum(),
00063 msg->getDataType(),
00064 msg->getMessageDefinition(),
00065 connect_cb,
00066 disconnect_cb);
00067 opts.latch = false;
00068 pub_ = pnh_.advertise(opts);
00069 advertised_ = true;
00070
00071 sub_.shutdown();
00072 }
00073 else if (pub_.getNumSubscribers() > 0) {
00074 pub_.publish(msg);
00075 }
00076 }
00077
00078 void Relay::connectCb()
00079 {
00080 boost::mutex::scoped_lock lock(mutex_);
00081 NODELET_DEBUG("connectCB");
00082 if (advertised_) {
00083 if (pub_.getNumSubscribers() > 0) {
00084 if (!subscribing_) {
00085 NODELET_DEBUG("suscribe");
00086 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00087 &Relay::inputCallback, this, th_);
00088 subscribing_ = true;
00089 }
00090 }
00091 }
00092 }
00093
00094 void Relay::disconnectCb()
00095 {
00096 boost::mutex::scoped_lock lock(mutex_);
00097 NODELET_DEBUG("disconnectCb");
00098 if (advertised_) {
00099 if (pub_.getNumSubscribers() == 0) {
00100 if (subscribing_) {
00101 NODELET_DEBUG("disconnect");
00102 sub_.shutdown();
00103 subscribing_ = false;
00104 }
00105 }
00106 }
00107 }
00108
00109 }
00110
00111 typedef jsk_topic_tools::Relay Relay;
00112 PLUGINLIB_EXPORT_CLASS(Relay, nodelet::Nodelet)