Skip to content

Commit 8b8ec7b

Browse files
authored
Merge pull request #3060 from SergioRAgostinho/thread
Transition from boost::thread to std::thread.
2 parents c3aeb68 + 3d23d5b commit 8b8ec7b

39 files changed

+129
-113
lines changed

common/include/pcl/common/boost.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,6 @@
5050
#include <boost/mpl/size.hpp>
5151
#include <boost/date_time/posix_time/posix_time.hpp>
5252
#include <boost/function.hpp>
53-
#include <boost/thread.hpp>
5453
#include <boost/signals2.hpp>
5554
#include <boost/signals2/slot.hpp>
5655
#include <boost/algorithm/string.hpp>

common/include/pcl/common/time_trigger.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,10 +43,11 @@
4343
#include <boost/function.hpp>
4444
#include <boost/thread.hpp>
4545
#include <boost/signals2.hpp>
46+
#endif
4647

4748
#include <condition_variable>
4849
#include <mutex>
49-
#endif
50+
#include <thread>
5051

5152
namespace pcl
5253
{
@@ -101,7 +102,7 @@ namespace pcl
101102
bool quit_;
102103
bool running_;
103104

104-
boost::thread timer_thread_;
105+
std::thread timer_thread_;
105106
std::condition_variable condition_;
106107
std::mutex condition_mutex_;
107108
};

common/src/time_trigger.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ pcl::TimeTrigger::TimeTrigger (double interval, const callback_type& callback)
4949
, condition_ ()
5050
, condition_mutex_ ()
5151
{
52-
timer_thread_ = boost::thread (boost::bind (&TimeTrigger::thread_function, this));
52+
timer_thread_ = std::thread (&TimeTrigger::thread_function, this);
5353
registerCallback (callback);
5454
}
5555

@@ -63,7 +63,7 @@ pcl::TimeTrigger::TimeTrigger (double interval)
6363
, condition_ ()
6464
, condition_mutex_ ()
6565
{
66-
timer_thread_ = boost::thread (boost::bind (&TimeTrigger::thread_function, this));
66+
timer_thread_ = std::thread (&TimeTrigger::thread_function, this);
6767
}
6868

6969
//////////////////////////////////////////////////////////////////////////////////////////////

gpu/kinfu_large_scale/tools/record_maps_rgb.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -323,11 +323,11 @@ main (int argc, char** argv)
323323
buff.setCapacity (buff_size);
324324
std::cout << "Starting the producer and consumer threads..." << std::endl;
325325
std::cout << "Press Ctrl-C to end" << std::endl;
326-
boost::thread producer (grabAndSend);
326+
std::thread producer (grabAndSend);
327327
std::this_thread::sleep_for(2s);
328-
boost::thread consumer (receiveAndProcess);
329-
boost::thread consumer2 (receiveAndProcess);
330-
boost::thread consumer3 (receiveAndProcess);
328+
std::thread consumer (receiveAndProcess);
329+
std::thread consumer2 (receiveAndProcess);
330+
std::thread consumer3 (receiveAndProcess);
331331
signal (SIGINT, ctrlC);
332332
producer.join ();
333333
{

io/include/pcl/io/boost.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,6 @@
4747
#include <boost/numeric/conversion/cast.hpp>
4848
#include <boost/thread/mutex.hpp>
4949
#include <boost/thread/condition.hpp>
50-
#include <boost/thread.hpp>
5150
#include <boost/filesystem.hpp>
5251
#include <boost/bind.hpp>
5352
#include <boost/cstdint.hpp>

io/include/pcl/io/davidsdk_grabber.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@
4747

4848
#include <david.h>
4949

50+
#include <thread>
51+
5052
namespace pcl
5153
{
5254
struct PointXYZ;
@@ -217,7 +219,7 @@ namespace pcl
217219

218220
protected:
219221
/** @brief Grabber thread */
220-
boost::thread grabber_thread_;
222+
std::thread grabber_thread_;
221223

222224
/** @brief Boost point cloud signal */
223225
boost::signals2::signal<sig_cb_davidsdk_point_cloud>* point_cloud_signal_;

io/include/pcl/io/depth_sense/depth_sense_device_manager.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,8 @@
4545

4646
#include <DepthSense.hxx>
4747

48+
#include <thread>
49+
4850
namespace pcl
4951
{
5052

@@ -136,7 +138,7 @@ namespace pcl
136138
static boost::mutex mutex_;
137139

138140
/// Thread where the grabbing takes place.
139-
boost::thread depth_sense_thread_;
141+
std::thread depth_sense_thread_;
140142

141143
struct CapturedDevice
142144
{

io/include/pcl/io/dinast_grabber.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@
4747
#include <libusb-1.0/libusb.h>
4848
#include <boost/circular_buffer.hpp>
4949

50+
#include <thread>
51+
5052
namespace pcl
5153
{
5254
/** \brief Grabber for DINAST devices (i.e., IPA-1002, IPA-1110, IPA-2001)
@@ -206,7 +208,7 @@ namespace pcl
206208

207209
bool running_;
208210

209-
boost::thread capture_thread_;
211+
std::thread capture_thread_;
210212

211213
mutable boost::mutex capture_mutex_;
212214
boost::signals2::signal<sig_cb_dinast_point_cloud>* point_cloud_signal_;

io/include/pcl/io/ensenso_grabber.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,8 @@
5252

5353
#include <nxLib.h> // Ensenso SDK
5454

55+
#include <thread>
56+
5557
namespace pcl
5658
{
5759
struct PointXYZ;
@@ -434,7 +436,7 @@ namespace pcl
434436

435437
protected:
436438
/** @brief Grabber thread */
437-
boost::thread grabber_thread_;
439+
std::thread grabber_thread_;
438440

439441
/** @brief Boost point cloud signal */
440442
boost::signals2::signal<sig_cb_ensenso_point_cloud>* point_cloud_signal_;

io/include/pcl/io/hdl_grabber.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include <pcl/point_cloud.h>
4747
#include <boost/asio.hpp>
4848
#include <string>
49+
#include <thread>
4950

5051
#define HDL_Grabber_toRadians(x) ((x) * M_PI / 180.0)
5152

@@ -293,8 +294,8 @@ namespace pcl
293294
boost::asio::io_service hdl_read_socket_service_;
294295
boost::asio::ip::udp::socket *hdl_read_socket_;
295296
std::string pcap_file_name_;
296-
boost::thread *queue_consumer_thread_;
297-
boost::thread *hdl_read_packet_thread_;
297+
std::thread *queue_consumer_thread_;
298+
std::thread *hdl_read_packet_thread_;
298299
bool terminate_read_packet_thread_;
299300
pcl::RGB laser_rgb_mapping_[HDL_MAX_NUM_LASERS];
300301
float min_distance_threshold_;

0 commit comments

Comments
 (0)