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/block_nodelet.h"
00036
00037 #include <ros/advertise_options.h>
00038
00039 namespace jsk_topic_tools
00040 {
00041
00042
00043
00044 void Block::onInit()
00045 {
00046 pnh_ = getPrivateNodeHandle();
00047 pub_input_original_advertised_ = pub_output_advertised_ = false;
00048 sub_input_subscribing_ = sub_output_original_subscribing_ = false;
00049 pnh_.param("check_rate", check_rate_, 1.0);
00050 sub_input_
00051 = pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00052 &Block::inputCallback,
00053 this);
00054 sub_output_original_
00055 = pnh_.subscribe<topic_tools::ShapeShifter>(
00056 "output_original", 1,
00057 &Block::outputOriginalCallback,
00058 this);
00059 timer_ = pnh_.createTimer(ros::Duration(1 / check_rate_),
00060 &Block::timerCallback, this);
00061 }
00062
00063 void Block::timerCallback(const ros::TimerEvent& event)
00064 {
00065 NODELET_DEBUG("timerCallback");
00066 if (pub_input_original_advertised_ && pub_output_advertised_) {
00067
00068
00069
00070
00071 if (pub_output_.getNumSubscribers() > 0) {
00072 NODELET_DEBUG("subscribe input");
00073
00074 if (!sub_input_subscribing_) {
00075 sub_input_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00076 "input", 1,
00077 &Block::inputCallback,
00078 this);
00079 sub_input_subscribing_ = true;
00080 }
00081 if (!sub_output_original_subscribing_) {
00082 NODELET_DEBUG("subscribe output original");
00083 sub_output_original_
00084 = pnh_.subscribe<topic_tools::ShapeShifter>(
00085 "output_original", 1,
00086 &Block::outputOriginalCallback,
00087 this);
00088 sub_output_original_subscribing_ = true;
00089 }
00090 }
00091 else {
00092
00093 if (sub_input_subscribing_) {
00094 NODELET_DEBUG("shutdown input");
00095 sub_input_.shutdown();
00096 sub_input_subscribing_ = false;
00097 }
00098 if (sub_output_original_subscribing_) {
00099 NODELET_DEBUG("shutdown output_original");
00100 sub_output_original_.shutdown();
00101 sub_output_original_subscribing_ = false;
00102 }
00103 }
00104 }
00105 }
00106
00107 void Block::inputCallback(
00108 const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00109 {
00110 NODELET_DEBUG("inputCallback");
00111
00112 if (!pub_input_original_advertised_) {
00113 NODELET_DEBUG("advertise input_original");
00114 pub_input_original_ = msg->advertise(pnh_, "input_original", 1);
00115 pub_input_original_advertised_ = true;
00116
00117 if (pub_output_advertised_) {
00118 NODELET_DEBUG("shutdown input");
00119 sub_input_.shutdown();
00120 }
00121 else {
00122 NODELET_DEBUG("publish input_original");
00123 pub_input_original_.publish(msg);
00124 }
00125 }
00126 else {
00127 NODELET_DEBUG("publish input_original");
00128 pub_input_original_.publish(msg);
00129 }
00130 }
00131
00132 void Block::outputOriginalCallback(
00133 const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00134 {
00135 NODELET_DEBUG("outputOriginalCallback");
00136
00137 if (!pub_output_advertised_) {
00138 NODELET_DEBUG("advertise output");;
00139 pub_output_ = msg->advertise(pnh_, "output", 1);
00140 pub_output_advertised_ = true;
00141
00142 sub_output_original_.shutdown();
00143 if (pub_input_original_advertised_) {
00144 NODELET_DEBUG("shutdown input");
00145 sub_input_.shutdown();
00146 }
00147 else {
00148 NODELET_DEBUG("publish output");
00149 pub_output_.publish(msg);
00150 }
00151 }
00152 else {
00153 NODELET_DEBUG("publish output");
00154 pub_output_.publish(msg);
00155 }
00156 }
00157 }
00158
00159 typedef jsk_topic_tools::Block Block;
00160 PLUGINLIB_EXPORT_CLASS(Block, nodelet::Nodelet)
00161