nodelet.cc
Go to the documentation of this file.
1 /*
2  * License: Modified BSD Software License Agreement
3  *
4  * $Id$
5  */
6 
12 #include <string>
13 #include <boost/thread.hpp>
14 
15 #include <ros/ros.h>
17 #include <nodelet/nodelet.h>
18 
19 #include "driver.h"
20 
21 namespace o3m151_driver
22 {
23 
25 {
26 public:
27 
29  running_(false)
30  {}
31 
33  {
34  if (running_)
35  {
36  NODELET_INFO("shutting down driver thread");
37  running_ = false;
38  deviceThread_->join();
39  NODELET_INFO("driver thread stopped");
40  }
41  }
42 
43 private:
44 
45  virtual void onInit(void);
46  virtual void devicePoll(void);
47 
48  volatile bool running_;
50 
52 };
53 
55 {
56  // start the driver
58 
59  // spawn device poll thread
60  running_ = true;
62  (new boost::thread(boost::bind(&DriverNodelet::devicePoll, this)));
63 }
64 
67 {
68  while(ros::ok())
69  {
70  // poll device until end of file
71  running_ = dvr_->poll();
72  if (!running_)
73  break;
74  }
75  running_ = false;
76 }
77 
78 } // namespace o3m151_driver
79 
80 // Register this plugin with pluginlib. Names must match nodelet_o3m151.xml.
81 //
82 // parameters are: package, class name, class type, base class type
virtual void devicePoll(void)
Device poll thread main loop.
Definition: nodelet.cc:66
volatile bool running_
device thread is running
Definition: nodelet.cc:48
PLUGINLIB_DECLARE_CLASS(o3m151_driver, DriverNodelet, o3m151_driver::DriverNodelet, nodelet::Nodelet)
boost::shared_ptr< boost::thread > deviceThread_
Definition: nodelet.cc:49
ros::NodeHandle & getPrivateNodeHandle() const
virtual void onInit(void)
Definition: nodelet.cc:54
ROSCPP_DECL bool ok()
ros::NodeHandle & getNodeHandle() const
#define NODELET_INFO(...)
boost::shared_ptr< O3M151Driver > dvr_
driver implementation class
Definition: nodelet.cc:51


o3m151_driver
Author(s): Vincent Rousseau
autogenerated on Mon Jun 10 2019 14:07:55