driver_node.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
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/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage 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  *********************************************************************/
34 
35 // Author: Blaise Gassend
36 #ifndef __DRIVER_BASE__DRIVER_NODE_H__
37 #define __DRIVER_BASE__DRIVER_NODE_H__
38 
40 #include <self_test/self_test.h>
41 #include <ros/node_handle.h>
42 #include <boost/thread.hpp>
43 #include <boost/bind.hpp>
44 #include <driver_base/SensorLevels.h>
45 #include <signal.h>
46 #include <dynamic_reconfigure/server.h>
47 
48 namespace driver_base
49 {
50 
51 class AbstractDriverNode
52 {
53 public:
54  static int ctrl_c_hit_count_;
55 
56  static void hupCalled(int sig)
57  {
58  ROS_WARN("Unexpected SIGHUP caught. Ignoring it.");
59  }
60 
61  static void sigCalled(int sig)
62  {
64  }
65 };
66 
67 template <class DriverType>
68 int main(int argc, char **argv, std::string name)
69 {
72  ros::init(argc, argv, name);
73  //ros::init(argc, argv, name, ros::init_options::NoSigintHandler);
74  //signal(SIGINT, &AbstractDriverNode::sigCalled);
75  //signal(SIGTERM, &AbstractDriverNode::sigCalled);
76  signal(SIGHUP, &AbstractDriverNode::hupCalled);
77  ros::NodeHandle nh;
78  DriverType driver(nh);
79  return driver.spin();
81 }
82 
83 template <class Driver>
84 class DriverNode : public AbstractDriverNode
85 {
86 public:
87  //typedef char state_t;
88  typedef typename Driver::Config Config;
89 
90 protected:
91  // Hooks
92  virtual void addDiagnostics() = 0;
93  virtual void addStoppedTests() = 0;
94  virtual void addOpenedTests() = 0;
95  virtual void addRunningTests() = 0;
96  virtual void reconfigureHook(int level) = 0;
97 
98  // Helper classes
103 
104  Driver driver_;
105  dynamic_reconfigure::Server<Config> reconfigure_server_;
107  // driver_ declaration must precede reconfigure_server_ for constructor
108  // calling order reasons.
109 
110 private:
111  // Subscriber tracking
112  int num_subscribed_topics_; // Number of topics that have subscribers.
113 
114  //static const state_t DISABLED = 0;
115  //static const state_t LAZY_ON = 1;
116  //static const state_t ALWAYS_ON = 2;
117  //static const state_t SELF_TEST = 3;
118  //static const state_t EXITING = 4;
119 
120  //state_t state_;
121 
123 
124  int exit_status_;
125 
126  // The device
127  typedef typename Driver::state_t drv_state_t;
128 
130 
132 
133  void reconfigure(Config &config, uint32_t level)
134  {
136  ROS_DEBUG("Reconfigure called at level %x.", level);
137  boost::recursive_mutex::scoped_lock lock(driver_.mutex_);
138 
139  drv_state_t orig_state = driver_.getState();
140 
141  if ((level | driver_base::SensorLevels::RECONFIGURE_STOP) == level)
142  {
143  driver_.stop();
145  ROS_ERROR("Failed to stop streaming before reconfiguring. Reconfiguration may fail.");
146  }
147 
148  if ((level | driver_base::SensorLevels::RECONFIGURE_CLOSE) == level)
149  {
150  driver_.close();
151  if (!driver_.isClosed())
152  ROS_ERROR("Failed to close device before reconfiguring. Reconfiguration may fail.");
153  }
154 
155  driver_.config_update(config, level);
156  config = driver_.config_;
157  reconfigureHook(level);
158 
159  driver_.goState(orig_state);
160 
161  /* Other errors will show up when this happens. No need to have it
162  * here.
163  if (driver_.getState() != orig_state)
164  {
165  ROS_ERROR("Failed to resume original device state after reconfiguring. The requested configuration may contain errors.");
166  }
167  */
168 
169  ROS_DEBUG("Reconfigure completed.");
170  }
171 
172 private:
173 /* void connectCallback(const ros::PublisherPtr &pub)
174  {
175  if (pub.numSubscribers == 1)
176  num_subscribed_topics_++;
177 
178  if (num_subscribed_topics_ == 1)
179  start();
180  }
181 
182  void disconnectCallback(const ros::PublisherPtr &pub)
183  {
184  if (pub.numSubscribers == 0)
185  num_subscribed_topics_++;
186 
187  if (num_subscribed_topics_ == 0)
188  stop();
189  }*/
190 
191  void prepareDiagnostics()
192  {
195  addDiagnostics();
196  }
197 
199  {
200  if (driver_.isRunning())
201  stat.summary(0, "OK");
202  else
203  stat.summary(2, "not running");
204 
205  stat.add("Driver state:", driver_.getStateName());
206  stat.add("Latest status message:", driver_.getStatusMessage());
208  }
209 
210  void prepareSelfTests()
211  {
212  self_test_.add( "Interruption Test", this, &DriverNode::interruptionTest );
213  addStoppedTests();
214  self_test_.add( "Connection Test", this, &DriverNode::openTest );
215  self_test_.add( "ID Test", this, &DriverNode::idTest );
216  addOpenedTests();
217  self_test_.add( "Start Streaming Test", this, &DriverNode::runTest );
218  addRunningTests();
219  self_test_.add( "Stop Streaming Test", this, &DriverNode::stopTest );
220  self_test_.add( "Disconnection Test", this, &DriverNode::closeTest );
221  self_test_.add( "Resume Activity", this, &DriverNode::resumeTest );
222  }
223 
225  {
227  driver_.goClosed();
228 
230 
231  if (num_subscribed_topics_ > 0)
232  status.summary(1, "There were active subscribers. Running of self test interrupted operations.");
233  else if (s != Driver::CLOSED)
234  status.summaryf(2, "Could not close device, currently in state %s.", Driver::getStateName(s).c_str());
235  else
236  status.summary(0, "No operation interrupted.");
237  }
238 
240  {
241  const int max_tries = 5;
242  ROS_ASSERT(max_tries > 0);
243  int retries;
244  drv_state_t current_state;
245  for (retries = 0; retries < max_tries; retries++)
246  {
247  sleep(1);
248  driver_.goState(target_state);
249 
250  current_state = driver_.getState();
251  if (current_state == target_state)
252  break;
253  }
254 
255  std::string target_state_name = Driver::getStateName(target_state);
256  std::string current_state_name = Driver::getStateName(current_state);
257 
258  // We carefully avoid rechecking the state here, as it may have
259  // changed since we last checked. We aren't here to check that we
260  // stayed in the target state, just want to check that we made it
261  // there...
262  if (retries >= max_tries)
263  status.summaryf(2, "Failed to go to %s state despite %u retries, now in state %s.", target_state_name.c_str(), retries, current_state_name.c_str());
264  else if (retries)
265  status.summaryf(1, "Successfully went to state %s after %u retries.", target_state_name.c_str(), retries);
266  else
267  status.summaryf(0, "Successfully went to state %s.", target_state_name.c_str());
268  }
269 
271  {
273  }
274 
276  {
277  std::string ID = driver_.getID();
278  if (ID.compare(""))
279  {
280  status.summaryf(0, "Device ID is %s", ID.c_str());
281  self_test_.setID(ID);
282  }
283  else
284  status.summaryf(2, "Error reading Device ID");
285  }
286 
288  {
290  }
291 
293  {
295  }
296 
298  {
300  }
301 
303  {
305  }
306 
307 public:
308  virtual ~DriverNode() {}
309 
310  int spin()
311  {
314  typename dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(&DriverNode::reconfigure, this, _1, _2);
315  reconfigure_server_.setCallback(f);
316 
317  ros_thread_.reset(new boost::thread(boost::bind(&ros::spin)));
319  assert(ros_thread_);
320 
321  driver_.goRunning();
322 
324  std::string last_status_message;
325  while (node_handle_.ok() && /*state_ != EXITING &&*/ !ctrl_c_hit_count_)
326  {
327  {
328  // Must lock here, otherwise operations like reconfigure will cause
329  // the test to pass, and an unnecessary restart will happen when the
330  // reconfigure is done.
331  boost::recursive_mutex::scoped_lock lock_(driver_.mutex_);
332 
333  if (!driver_.isRunning())
334  {
335  std::string new_status_message = driver_.getStatusMessage();
336  if ((last_status_message != new_status_message || driver_.getRecoveryComplete())
337  && !driver_.getStatusOk())
338  {
339  ROS_ERROR("%s", new_status_message.c_str());
341  last_status_message = new_status_message;
342  }
344  driver_.goClosed();
345  driver_.goRunning();
346  }
347 
350  }
351  ros::WallDuration(0.1).sleep();
352  }
353 
354  driver_.goClosed();
355 
356  ros::shutdown();
357 
358  if (ros_thread_ && !ros_thread_->timed_join((boost::posix_time::milliseconds) 2000))
359  {
360  ROS_ERROR("ROS thread did not die after two seconds. Pretending that it did. This is probably a bad sign.");
361  }
362  ros_thread_.reset();
363 
364  return 0;
365  }
366 
368  node_handle_(nh),
369  private_node_handle_("~"),
371  diagnostic_(),
372  reconfigure_server_(driver_.mutex_, ros::NodeHandle("~")),
373  driver_status_diagnostic_("Driver Status"),
374  driver_status_standard_diagnostic_("Driver Status", boost::bind(&DriverNode::statusDiagnostic, this, _1))
375  {
377  exit_status_ = 0;
378 
379  // Defer most initialization to spin so that virtual calls in derived
380  // classes will succeed.
381  }
382 };
383 
385 
386 // @todo exit status.
387 // @todo take over ctrl_c.
388 
389 };
390 
391 #endif
diagnostic_updater::CompositeDiagnosticTask::addTask
void addTask(DiagnosticTask *t)
driver_base::DriverNode::reconfigure_server_
dynamic_reconfigure::Server< Config > reconfigure_server_
Definition: driver_node.h:137
driver_base::DriverNode::driver_status_standard_diagnostic_
diagnostic_updater::FunctionDiagnosticTask driver_status_standard_diagnostic_
Definition: driver_node.h:163
ros::WallDuration::sleep
bool sleep() const
driver_base::DriverNode::self_test_
self_test::TestRunner self_test_
Definition: driver_node.h:133
driver_base::DriverNode::runTest
void runTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:319
node_handle.h
driver_base::DriverNode::driver_
Driver driver_
Definition: driver_node.h:136
driver_base::Driver::goClosed
bool goClosed()
Definition: driver.h:237
driver_base::DriverNode::openTest
void openTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:302
driver_base::AbstractDriverNode::ctrl_c_hit_count_
static int ctrl_c_hit_count_
Definition: driver_node.h:118
driver_base::DriverNode::prepareSelfTests
void prepareSelfTests()
Definition: driver_node.h:242
driver_base::AbstractDriverNode::sigCalled
static void sigCalled(int sig)
Definition: driver_node.h:125
boost::shared_ptr< boost::thread >
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
driver_base::DriverNode::reconfigureHook
virtual void reconfigureHook(int level)=0
driver_base::Driver::mutex_
boost::recursive_mutex mutex_
Definition: driver.h:162
s
XmlRpcServer s
ros
driver_base::DriverNode::statusDiagnostic
void statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: driver_node.h:230
driver_base::DriverNode::drv_state_t
Driver::state_t drv_state_t
Definition: driver_node.h:159
driver_base::Driver::getStateName
const std::string getStateName()
Definition: driver.h:288
driver_base::DriverNode::addOpenedTests
virtual void addOpenedTests()=0
driver_base::Driver::goState
bool goState(state_t target)
Definition: driver.h:168
driver_base::DriverNode::closeTest
void closeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:329
diagnostic_updater::Updater
ros::shutdown
ROSCPP_DECL void shutdown()
driver_base::AbstractDriverNode
Definition: driver_node.h:83
boost
driver_base::DriverNode::driver_status_diagnostic_
diagnostic_updater::CompositeDiagnosticTask driver_status_diagnostic_
Definition: driver_node.h:138
driver_base::DriverNode
Definition: driver_node.h:116
driver_base::DriverNode::reliableGoStateTest
void reliableGoStateTest(diagnostic_updater::DiagnosticStatusWrapper &status, drv_state_t target_state)
Definition: driver_node.h:271
driver_base::Driver::state_t
char state_t
Definition: driver.h:135
driver_base::main
int main(int argc, char **argv, std::string name)
Definition: driver_node.h:100
self_test.h
driver_base::Driver::isClosed
bool isClosed()
Definition: driver.h:272
driver_base::DriverNode::diagnostic_
diagnostic_updater::Updater diagnostic_
Definition: driver_node.h:134
diagnostic_updater.h
f
f
driver_base::DriverNode::ros_thread_
boost::shared_ptr< boost::thread > ros_thread_
Definition: driver_node.h:154
driver_base::Driver
Definition: driver.h:100
self_test::TestRunner::add
void add(const std::string &name, TaskFunction f)
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
driver_base::DriverNode::addStoppedTests
virtual void addStoppedTests()=0
ROS_DEBUG
#define ROS_DEBUG(...)
driver_base
Definition: driver.h:46
driver_base::Driver::getRecoveryComplete
bool getRecoveryComplete()
Definition: driver.h:316
driver_base::Driver::OPENED
static const state_t OPENED
Definition: driver.h:165
driver_base::Driver::getID
virtual std::string getID()=0
driver_base::Driver::getState
state_t getState()
Definition: driver.h:283
driver_base::Driver::clearRecoveryComplete
void clearRecoveryComplete()
Definition: driver.h:321
driver_base::DriverNode::private_node_handle_
ros::NodeHandle private_node_handle_
Definition: driver_node.h:132
driver_base::DriverNode::interruptionTest
void interruptionTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:256
driver_base::DriverNode::node_handle_
ros::NodeHandle node_handle_
Definition: driver_node.h:131
ROS_WARN
#define ROS_WARN(...)
self_test::TestRunner
driver_base::DriverNode::stopTest
void stopTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:324
diagnostic_updater::CompositeDiagnosticTask
self_test::TestRunner::setID
void setID(std::string id)
driver_base::Driver::CLOSED
static const state_t CLOSED
Definition: driver.h:164
driver_base::Driver::RUNNING
static const state_t RUNNING
Definition: driver.h:166
driver_base::Driver::getStatusOk
bool getStatusOk()
Definition: driver.h:311
driver_base::DriverNode::addDiagnostics
virtual void addDiagnostics()=0
diagnostic_updater::Updater::update
void update()
ros::NodeHandle::ok
bool ok() const
driver_base::DriverNode::spin
int spin()
Definition: driver_node.h:342
driver_base::DriverNode::resumeTest
void resumeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:334
driver_base::Driver::isStopped
bool isStopped()
Definition: driver.h:277
driver_base::DriverNode::prepareDiagnostics
void prepareDiagnostics()
Definition: driver_node.h:223
self_test::TestRunner::checkTest
void checkTest()
driver_base::DriverNode::num_subscribed_topics_
int num_subscribed_topics_
Definition: driver_node.h:144
ROS_ERROR
#define ROS_ERROR(...)
driver_base::DriverNode::addRunningTests
virtual void addRunningTests()=0
driver_base::DriverNode::reconfigure
void reconfigure(Config &config, uint32_t level)
Definition: driver_node.h:165
diagnostic_updater::GenericFunctionDiagnosticTask
diagnostic_updater::DiagnosticStatusWrapper
ros::spin
ROSCPP_DECL void spin()
driver_base::DriverNode::idTest
void idTest(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: driver_node.h:307
driver_base::Driver::getStatusMessage
const std::string getStatusMessage()
Definition: driver.h:326
driver_base::DriverNode::~DriverNode
virtual ~DriverNode()
Definition: driver_node.h:340
ros::WallDuration
ROS_ASSERT
#define ROS_ASSERT(cond)
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
driver_base::DriverNode::pre_self_test_driver_state_
drv_state_t pre_self_test_driver_state_
Definition: driver_node.h:161
driver_base::Driver::goRunning
bool goRunning()
Definition: driver.h:227
driver_base::AbstractDriverNode::hupCalled
static void hupCalled(int sig)
Definition: driver_node.h:120
diagnostic_updater::DiagnosticStatusWrapper::summaryf
void summaryf(unsigned char lvl, const char *format,...)
driver_base::Driver::close
bool close()
Definition: driver.h:257
driver_base::DriverNode::exit_status_
int exit_status_
Definition: driver_node.h:156
driver_base::DriverNode::DriverNode
DriverNode(ros::NodeHandle &nh)
Definition: driver_node.h:399
ros::NodeHandle
driver_base::DriverNode::Config
Driver::Config Config
Definition: driver_node.h:120
driver_base::Driver::isRunning
bool isRunning()
Definition: driver.h:262
driver_base::Driver::stop
bool stop()
Definition: driver.h:242


driver_base
Author(s): Blaise Gassend
autogenerated on Wed Mar 2 2022 00:11:50