relay_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
36 
37 namespace jsk_topic_tools
38 {
39 
41  {
42  output_topic_name_ = "output";
45  // setup diagnostic
46  diagnostic_updater_.reset(
48  diagnostic_updater_->setHardwareID(getName());
50  getName() + "::Relay",
51  boost::bind(
52  &Relay::updateDiagnostic, this, _1));
53  double vital_rate;
54  pnh_.param("vital_rate", vital_rate, 1.0);
55  vital_checker_.reset(
56  new jsk_topic_tools::VitalChecker(1 / vital_rate));
57  diagnostic_updater_->start();
59  "input", 1,
60  &Relay::inputCallback, this);
62  "change_output_topic", &Relay::changeOutputTopicCallback, this);
63  }
64 
67  {
68  boost::mutex::scoped_lock lock(mutex_);
70  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
71  "not initialized. Is "
72  + pnh_.resolveName("input") + " active?");
73  }
74  else if (connection_status_ == SUBSCRIBED) {
75  if (vital_checker_->isAlive()) {
76  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
77  "subscribed: " + pnh_.resolveName("output"));
78  }
79  else {
80  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
81  "subscribed but no input. Is "
82  + pnh_.resolveName("input") + " active?");
83  }
84  vital_checker_->registerStatInfo(stat);
85  }
86  else if (connection_status_ == NOT_SUBSCRIBED) {
87  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
88  "not subscribed: " + pnh_.resolveName("output"));
89  }
90  stat.add("input topic", pnh_.resolveName("input"));
91  stat.add("output topic", pnh_.resolveName("output"));
92  }
93 
95  {
96  boost::mutex::scoped_lock lock(mutex_);
98  // this block is called only once
99  // in order to advertise topic.
100  // we need to subscribe at least one message
101  // in order to detect message definition.
104  // shutdown subscriber
105  sub_.shutdown();
106  sample_msg_ = msg;
107  }
108  else if (pub_.getNumSubscribers() > 0) {
109  vital_checker_->poke();
110  pub_.publish(msg);
111  }
112  }
113 
115  {
116  boost::mutex::scoped_lock lock(mutex_);
117  NODELET_DEBUG("connectCB");
119  if (pub_.getNumSubscribers() > 0) {
121  NODELET_DEBUG("suscribe");
123  &Relay::inputCallback, this);
125  }
126  }
127  }
128  }
129 
131  {
132  boost::mutex::scoped_lock lock(mutex_);
133  NODELET_DEBUG("disconnectCb");
135  if (pub_.getNumSubscribers() == 0) {
137  NODELET_DEBUG("disconnect");
138  sub_.shutdown();
140  }
141  }
142  }
143  }
144 
147  const std::string& topic)
148  {
150  = boost::bind( &Relay::connectCb, this);
151  ros::SubscriberStatusCallback disconnect_cb
152  = boost::bind( &Relay::disconnectCb, this);
153  ros::AdvertiseOptions opts(topic, 1,
154  msg->getMD5Sum(),
155  msg->getDataType(),
156  msg->getMessageDefinition(),
157  connect_cb,
158  disconnect_cb);
159  opts.latch = false;
160  return pnh_.advertise(opts);
161  }
162 
164  jsk_topic_tools::ChangeTopic::Request &req,
165  jsk_topic_tools::ChangeTopic::Response &res)
166  {
167  boost::mutex::scoped_lock lock(mutex_);
168  output_topic_name_ = req.topic;
169  if (sample_msg_) { // we can advertise it!
171  }
172  return true;
173  }
174 }
175 
ros::Publisher pub_
Definition: relay_nodelet.h:70
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
virtual void disconnectCb()
boost::shared_ptr< topic_tools::ShapeShifter const > sample_msg_
Definition: relay_nodelet.h:67
virtual void connectCb()
void summary(unsigned char lvl, const std::string s)
ros::ServiceServer change_output_topic_srv_
Definition: relay_nodelet.h:74
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
const std::string & getName() const
PLUGINLIB_EXPORT_CLASS(jsk_topic_tools::Snapshot, nodelet::Nodelet)
ros::NodeHandle pnh_
Definition: relay_nodelet.h:73
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::NodeHandle & getPrivateNodeHandle() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual ros::Publisher advertise(boost::shared_ptr< topic_tools::ShapeShifter const > msg, const std::string &topic)
VitalChecker::Ptr vital_checker_
Definition: relay_nodelet.h:81
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
uint32_t getNumSubscribers() const
std::string output_topic_name_
Definition: relay_nodelet.h:68
virtual bool changeOutputTopicCallback(jsk_topic_tools::ChangeTopic::Request &req, jsk_topic_tools::ChangeTopic::Response &res)
jsk_topic_tools::Relay Relay
void add(const std::string &key, const T &val)
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
Pointer to TimeredDiagnosticUpdater to call updateDiagnostic(diagnostic_updater::DiagnosticStatusWrap...
Definition: relay_nodelet.h:80
virtual void inputCallback(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
ConnectionStatus connection_status_
Definition: relay_nodelet.h:72
#define NODELET_DEBUG(...)
ros::Subscriber sub_
Definition: relay_nodelet.h:71


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