-
Notifications
You must be signed in to change notification settings - Fork 5
/
Copy pathboost_apply.cpp
61 lines (50 loc) · 1.25 KB
/
boost_apply.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
#include <string>
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include "rsdriver.h"
volatile sig_atomic_t flag = 1;
namespace rslidar_driver
{
class DriverNodelet : public nodelet::Nodelet
{
public:
DriverNodelet() : running_(false)
{
}
~DriverNodelet()
{
if (running_)
{
NODELET_INFO("shutting down driver thread");
running_ = false;
deviceThread_->join();
NODELET_INFO("driver thread stopped");
}
}
private:
virtual void onInit(void);
virtual void devicePoll(void);
volatile bool running_; ///< device thread is running
boost::shared_ptr<boost::thread> deviceThread_;
boost::shared_ptr<rslidarDriver> dvr_; ///< driver implementation class
};
void DriverNodelet::onInit()
{
// start the driver
dvr_.reset(new rslidarDriver(getNodeHandle(), getPrivateNodeHandle()));
// spawn device poll thread
running_ = true;
deviceThread_ = boost::shared_ptr<boost::thread>(new boost::thread(boost::bind(&DriverNodelet::devicePoll, this)));
// NODELET_INFO("DriverNodelet onInit");
}
/** @brief Device poll thread main loop. */
void DriverNodelet::devicePoll()
{
while (ros::ok() && dvr_->poll())
{
ros::spinOnce();
}
}
}