gscam_nodelet.cpp
Go to the documentation of this file.
1 
2 #include <ros/ros.h>
3 #include <nodelet/nodelet.h>
5 #include <gscam/gscam_nodelet.h>
6 
8 
9 namespace gscam {
10  GSCamNodelet::GSCamNodelet() :
11  nodelet::Nodelet(),
12  gscam_driver_(NULL),
13  stream_thread_(NULL)
14  {
15  }
16 
18  {
19  stream_thread_->join();
20  }
21 
23  {
24  gscam_driver_.reset(new gscam::GSCam(this->getNodeHandle(), this->getPrivateNodeHandle()));
25  stream_thread_.reset(new boost::thread(boost::bind(&GSCam::run, gscam_driver_.get())));
26  }
27 }
virtual void onInit()
ros::NodeHandle & getPrivateNodeHandle() const
boost::scoped_ptr< GSCam > gscam_driver_
Definition: gscam_nodelet.h:21
boost::scoped_ptr< boost::thread > stream_thread_
Definition: gscam_nodelet.h:22
Definition: gscam.h:20
ros::NodeHandle & getNodeHandle() const
void run()
Definition: gscam.cpp:413
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


gscam
Author(s): Jonathan Bohren , Graylin Trevor Jay , Christopher Crick
autogenerated on Mon Jun 10 2019 13:26:59