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/passthrough_nodelet.h"
00036
00037 namespace jsk_topic_tools
00038 {
00053 void Passthrough::onInit()
00054 {
00055 advertised_ = false;
00056 publish_requested_ = false;
00057 pnh_ = getPrivateNodeHandle();
00058 subscribing_ = true;
00059 pnh_.param("default_duration", default_duration_, 10.0);
00060 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00061 "input", 1,
00062 &Passthrough::inputCallback, this);
00063 request_duration_srv_ = pnh_.advertiseService(
00064 "request_duration", &Passthrough::requestDurationCallback, this);
00065 request_srv_ = pnh_.advertiseService(
00066 "request", &Passthrough::requestCallback, this);
00067 stop_srv_ = pnh_.advertiseService(
00068 "stop", &Passthrough::stopCallback, this);
00069 }
00070
00071 bool Passthrough::stopCallback(
00072 std_srvs::Empty::Request &req,
00073 std_srvs::Empty::Response &res)
00074 {
00075 boost::mutex::scoped_lock lock(mutex_);
00076
00077 if (!publish_requested_) {
00078 NODELET_DEBUG("already stoppped");
00079 }
00080 publish_requested_ = false;
00081 return true;
00082 }
00083
00084 void Passthrough::requestDurationCallbackImpl(
00085 const ros::Duration& duration)
00086 {
00087 boost::mutex::scoped_lock lock(mutex_);
00088
00089 if (duration == ros::Duration(0)) {
00090 end_time_ = ros::Time(0);
00091 publish_requested_ = true;
00092 }
00093 else {
00094 ros::Time now = ros::Time::now();
00095 if (publish_requested_) {
00096
00097 if (end_time_ < now + duration) {
00098 end_time_ = now + duration;
00099 }
00100 }
00101 else {
00102 publish_requested_ = true;
00103 end_time_ = now + duration;
00104 }
00105 }
00106 if (!subscribing_) {
00107 NODELET_DEBUG("suscribe");
00108 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00109 "input", 1,
00110 &Passthrough::inputCallback, this);
00111 subscribing_ = true;
00112 }
00113 }
00114
00115 bool Passthrough::requestDurationCallback(
00116 jsk_topic_tools::PassthroughDuration::Request &req,
00117 jsk_topic_tools::PassthroughDuration::Response &res)
00118 {
00119 requestDurationCallbackImpl(req.duration);
00120 return true;
00121 }
00122
00123 bool Passthrough::requestCallback(
00124 std_srvs::Empty::Request &req,
00125 std_srvs::Empty::Response &res)
00126 {
00127 requestDurationCallbackImpl(ros::Duration(default_duration_));
00128 return true;
00129 }
00130
00131 void Passthrough::inputCallback(
00132 const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00133 {
00134 boost::mutex::scoped_lock lock(mutex_);
00135 if (!advertised_) {
00136
00137
00138
00139
00140 pub_ = advertise(msg, "output");
00141 advertised_ = true;
00142 }
00143 if (publish_requested_) {
00144 ros::Time now = ros::Time::now();
00145 if (end_time_ == ros::Time(0) ||
00146 end_time_ > now) {
00147 pub_.publish(msg);
00148 }
00149
00150 if (end_time_ != ros::Time(0) && end_time_ < now) {
00151 publish_requested_ = false;
00152 }
00153 }
00154 if (!publish_requested_) {
00155
00156 sub_.shutdown();
00157 subscribing_ = false;
00158 }
00159 }
00160
00161 void Passthrough::connectCb()
00162 {
00163 boost::mutex::scoped_lock lock(mutex_);
00164 NODELET_DEBUG("connectCB");
00165 if (advertised_) {
00166 if (pub_.getNumSubscribers() > 0) {
00167 if (!subscribing_ && publish_requested_) {
00168 NODELET_DEBUG("suscribe");
00169 sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00170 "input", 1,
00171 &Passthrough::inputCallback, this);
00172 subscribing_ = true;
00173 }
00174 }
00175 }
00176 }
00177
00178 void Passthrough::disconnectCb()
00179 {
00180 boost::mutex::scoped_lock lock(mutex_);
00181 NODELET_DEBUG("disconnectCb");
00182 if (advertised_) {
00183 if (pub_.getNumSubscribers() == 0) {
00184 if (subscribing_) {
00185 NODELET_DEBUG("disconnect");
00186 sub_.shutdown();
00187 subscribing_ = false;
00188 }
00189 }
00190 }
00191 }
00192
00193
00194 ros::Publisher Passthrough::advertise(
00195 boost::shared_ptr<topic_tools::ShapeShifter const> msg,
00196 const std::string& topic)
00197 {
00198 ros::SubscriberStatusCallback connect_cb
00199 = boost::bind( &Passthrough::connectCb, this);
00200 ros::SubscriberStatusCallback disconnect_cb
00201 = boost::bind( &Passthrough::disconnectCb, this);
00202 ros::AdvertiseOptions opts(topic, 1,
00203 msg->getMD5Sum(),
00204 msg->getDataType(),
00205 msg->getMessageDefinition());
00206 opts.latch = true;
00207 return pnh_.advertise(opts);
00208 }
00209 }
00210
00211 typedef jsk_topic_tools::Passthrough Passthrough;
00212 PLUGINLIB_EXPORT_CLASS(Passthrough, nodelet::Nodelet)