Main Page
Namespaces
Classes
Files
File List
File Members
src
gscam_nodelet.cpp
Go to the documentation of this file.
1
2
#include <
ros/ros.h
>
3
#include <
nodelet/nodelet.h
>
4
#include <
pluginlib/class_list_macros.h
>
5
#include <
gscam/gscam_nodelet.h
>
6
7
PLUGINLIB_EXPORT_CLASS
(
gscam::GSCamNodelet
,
nodelet::Nodelet
)
8
9
namespace
gscam
{
10
GSCamNodelet::GSCamNodelet() :
11
nodelet
::Nodelet(),
12
gscam_driver_(NULL),
13
stream_thread_(NULL)
14
{
15
}
16
17
GSCamNodelet::~GSCamNodelet
()
18
{
19
stream_thread_
->join();
20
}
21
22
void
GSCamNodelet::onInit
()
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
}
gscam::GSCam
Definition:
gscam.h:22
gscam::GSCamNodelet::onInit
virtual void onInit()
Definition:
gscam_nodelet.cpp:22
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
nodelet.h
nodelet::Nodelet
gscam::GSCamNodelet::gscam_driver_
boost::scoped_ptr< GSCam > gscam_driver_
Definition:
gscam_nodelet.h:21
class_list_macros.h
gscam::GSCamNodelet
Definition:
gscam_nodelet.h:12
gscam::GSCamNodelet::~GSCamNodelet
~GSCamNodelet()
Definition:
gscam_nodelet.cpp:17
gscam::GSCamNodelet::stream_thread_
boost::scoped_ptr< boost::thread > stream_thread_
Definition:
gscam_nodelet.h:22
gscam
Definition:
gscam.h:20
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
ros.h
gscam::GSCam::run
void run()
Definition:
gscam.cpp:413
nodelet
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
gscam_nodelet.h
gscam
Author(s): Jonathan Bohren
, Graylin Trevor Jay
, Christopher Crick
autogenerated on Wed Jun 5 2019 21:03:34