nodelet.cpp
Go to the documentation of this file.
1 /* $Id$ */
2 
3 /*********************************************************************
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (c) 2010 Jack O'Quin
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the author nor other contributors may be
20 * used to endorse or promote products derived from this software
21 * without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36 
37 #include <signal.h>
38 
39 #include <boost/thread.hpp>
40 
41 #include <ros/ros.h>
43 #include <nodelet/nodelet.h>
44 
45 #include "driver1394.h"
46 
55 {
56 public:
58  running_(false)
59  {}
60 
62  {
63  if (running_)
64  {
65  NODELET_INFO("shutting down driver thread");
66  running_ = false;
67  deviceThread_->join();
68  NODELET_INFO("driver thread stopped");
69  }
70  dvr_->shutdown();
71  }
72 
73 private:
74  virtual void onInit();
75  virtual void devicePoll();
76 
77  volatile bool running_;
80 };
81 
87 {
90  ros::NodeHandle camera_nh(node, "camera");
91  dvr_.reset(new camera1394_driver::Camera1394Driver(priv_nh, camera_nh));
92  dvr_->setup();
93 
94  // spawn device thread
95  running_ = true;
97  (new boost::thread(boost::bind(&Camera1394Nodelet::devicePoll, this)));
98 }
99 
102 {
103  while (running_)
104  {
105  dvr_->poll();
106  }
107 }
108 
109 // Register this plugin with pluginlib. Names must match camera1394_nodelet.xml.
110 //
111 // parameters are: class type, base class type
volatile bool running_
device is running
Definition: nodelet.cpp:77
virtual void onInit()
Definition: nodelet.cpp:86
virtual void devicePoll()
Definition: nodelet.cpp:101
boost::shared_ptr< boost::thread > deviceThread_
Definition: nodelet.cpp:79
ros::NodeHandle & getPrivateNodeHandle() const
ROS driver interface for IIDC-compatible IEEE 1394 digital cameras.
ros::NodeHandle & getNodeHandle() const
#define NODELET_INFO(...)
boost::shared_ptr< camera1394_driver::Camera1394Driver > dvr_
Definition: nodelet.cpp:78
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Mon Jun 10 2019 12:52:31