Codebase list ros-opencv-apps / 896f1c9
Add patch for Boost 1.74 Jochen Sprickerhof 3 years ago
3 changed file(s) with 449 addition(s) and 1 deletion(s). Raw diff Collapse all Expand all
66 1 file changed, 1 insertion(+)
77
88 diff --git a/CMakeLists.txt b/CMakeLists.txt
9 index 852001b..f0d1aa1 100644
9 index 3b2dbb5..652f24b 100644
1010 --- a/CMakeLists.txt
1111 +++ b/CMakeLists.txt
1212 @@ -348,6 +348,7 @@ add_library(${PROJECT_NAME} SHARED
0 From: Jochen Sprickerhof <jspricke@debian.org>
1 Date: Tue, 15 Dec 2020 10:36:59 +0100
2 Subject: Switch to new boost/bind/bind.hpp
3
4 ---
5 include/opencv_apps/nodelet.h | 16 ++++++++--------
6 src/nodelet/adding_images_nodelet.cpp | 10 +++++-----
7 src/nodelet/camshift_nodelet.cpp | 2 +-
8 src/nodelet/color_filter_nodelet.cpp | 2 +-
9 src/nodelet/contour_moments_nodelet.cpp | 2 +-
10 src/nodelet/convex_hull_nodelet.cpp | 2 +-
11 src/nodelet/corner_harris_nodelet.cpp | 2 +-
12 src/nodelet/discrete_fourier_transform_nodelet.cpp | 2 +-
13 src/nodelet/edge_detection_nodelet.cpp | 2 +-
14 src/nodelet/face_detection_nodelet.cpp | 2 +-
15 src/nodelet/face_recognition_nodelet.cpp | 6 +++---
16 src/nodelet/fback_flow_nodelet.cpp | 2 +-
17 src/nodelet/find_contours_nodelet.cpp | 2 +-
18 src/nodelet/general_contours_nodelet.cpp | 2 +-
19 src/nodelet/goodfeature_track_nodelet.cpp | 2 +-
20 src/nodelet/hough_circles_nodelet.cpp | 2 +-
21 src/nodelet/hough_lines_nodelet.cpp | 2 +-
22 src/nodelet/lk_flow_nodelet.cpp | 2 +-
23 src/nodelet/people_detect_nodelet.cpp | 2 +-
24 src/nodelet/phase_corr_nodelet.cpp | 2 +-
25 src/nodelet/pyramids_nodelet.cpp | 2 +-
26 src/nodelet/segment_objects_nodelet.cpp | 2 +-
27 src/nodelet/simple_flow_nodelet.cpp | 2 +-
28 src/nodelet/smoothing_nodelet.cpp | 2 +-
29 src/nodelet/threshold_nodelet.cpp | 2 +-
30 src/nodelet/watershed_segmentation_nodelet.cpp | 2 +-
31 26 files changed, 39 insertions(+), 39 deletions(-)
32
33 diff --git a/include/opencv_apps/nodelet.h b/include/opencv_apps/nodelet.h
34 index d23e09f..f2c022f 100644
35 --- a/include/opencv_apps/nodelet.h
36 +++ b/include/opencv_apps/nodelet.h
37 @@ -155,8 +155,8 @@ protected:
38 ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size)
39 {
40 boost::mutex::scoped_lock lock(connection_mutex_);
41 - ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, _1);
42 - ros::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::connectionCallback, this, _1);
43 + ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
44 + ros::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
45 bool latch;
46 nh.param("latch", latch, false);
47 ros::Publisher ret = nh.advertise<T>(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch);
48 @@ -180,8 +180,8 @@ protected:
49 image_transport::Publisher advertiseImage(ros::NodeHandle& nh, const std::string& topic, int queue_size)
50 {
51 boost::mutex::scoped_lock lock(connection_mutex_);
52 - image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, _1);
53 - image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, _1);
54 + image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
55 + image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
56 bool latch;
57 nh.param("latch", latch, false);
58 image_transport::Publisher pub =
59 @@ -206,10 +206,10 @@ protected:
60 image_transport::CameraPublisher advertiseCamera(ros::NodeHandle& nh, const std::string& topic, int queue_size)
61 {
62 boost::mutex::scoped_lock lock(connection_mutex_);
63 - image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, _1);
64 - image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, _1);
65 - ros::SubscriberStatusCallback info_connect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, _1);
66 - ros::SubscriberStatusCallback info_disconnect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, _1);
67 + image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
68 + image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
69 + ros::SubscriberStatusCallback info_connect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
70 + ros::SubscriberStatusCallback info_disconnect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
71 bool latch;
72 nh.param("latch", latch, false);
73 image_transport::CameraPublisher pub = image_transport::ImageTransport(nh).advertiseCamera(
74 diff --git a/src/nodelet/adding_images_nodelet.cpp b/src/nodelet/adding_images_nodelet.cpp
75 index 2e83b3e..88952f0 100644
76 --- a/src/nodelet/adding_images_nodelet.cpp
77 +++ b/src/nodelet/adding_images_nodelet.cpp
78 @@ -122,13 +122,13 @@ private:
79 async_with_info_ =
80 boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(queue_size_);
81 async_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
82 - async_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
83 + async_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
84 }
85 else
86 {
87 sync_with_info_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyWithCameraInfo> >(queue_size_);
88 sync_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
89 - sync_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
90 + sync_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
91 }
92 }
93 else
94 @@ -137,13 +137,13 @@ private:
95 {
96 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
97 async_->connectInput(sub_image1_, sub_image2_);
98 - async_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
99 + async_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, boost::placeholders::_1, boost::placeholders::_2));
100 }
101 else
102 {
103 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
104 sync_->connectInput(sub_image1_, sub_image2_);
105 - sync_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
106 + sync_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, boost::placeholders::_1, boost::placeholders::_2));
107 }
108 }
109 }
110 @@ -259,7 +259,7 @@ public:
111 ////////////////////////////////////////////////////////
112 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
113 dynamic_reconfigure::Server<Config>::CallbackType f =
114 - boost::bind(&AddingImagesNodelet::reconfigureCallback, this, _1, _2);
115 + boost::bind(&AddingImagesNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
116 reconfigure_server_->setCallback(f);
117
118 pnh_->param("approximate_sync", approximate_sync_, true);
119 diff --git a/src/nodelet/camshift_nodelet.cpp b/src/nodelet/camshift_nodelet.cpp
120 index a16cfb6..bfa339a 100644
121 --- a/src/nodelet/camshift_nodelet.cpp
122 +++ b/src/nodelet/camshift_nodelet.cpp
123 @@ -388,7 +388,7 @@ public:
124
125 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
126 dynamic_reconfigure::Server<Config>::CallbackType f =
127 - boost::bind(&CamShiftNodelet::reconfigureCallback, this, _1, _2);
128 + boost::bind(&CamShiftNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
129 reconfigure_server_->setCallback(f);
130
131 img_pub_ = advertiseImage(*pnh_, "image", 1);
132 diff --git a/src/nodelet/color_filter_nodelet.cpp b/src/nodelet/color_filter_nodelet.cpp
133 index 90af18e..ff54432 100644
134 --- a/src/nodelet/color_filter_nodelet.cpp
135 +++ b/src/nodelet/color_filter_nodelet.cpp
136 @@ -182,7 +182,7 @@ public:
137
138 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
139 typename dynamic_reconfigure::Server<Config>::CallbackType f =
140 - boost::bind(&ColorFilterNodelet::reconfigureCallback, this, _1, _2);
141 + boost::bind(&ColorFilterNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
142 reconfigure_server_->setCallback(f);
143
144 img_pub_ = advertiseImage(*pnh_, "image", 1);
145 diff --git a/src/nodelet/contour_moments_nodelet.cpp b/src/nodelet/contour_moments_nodelet.cpp
146 index be453bf..f799c9a 100644
147 --- a/src/nodelet/contour_moments_nodelet.cpp
148 +++ b/src/nodelet/contour_moments_nodelet.cpp
149 @@ -284,7 +284,7 @@ public:
150
151 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
152 dynamic_reconfigure::Server<Config>::CallbackType f =
153 - boost::bind(&ContourMomentsNodelet::reconfigureCallback, this, _1, _2);
154 + boost::bind(&ContourMomentsNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
155 reconfigure_server_->setCallback(f);
156
157 img_pub_ = advertiseImage(*pnh_, "image", 1);
158 diff --git a/src/nodelet/convex_hull_nodelet.cpp b/src/nodelet/convex_hull_nodelet.cpp
159 index 9387182..371e1f7 100644
160 --- a/src/nodelet/convex_hull_nodelet.cpp
161 +++ b/src/nodelet/convex_hull_nodelet.cpp
162 @@ -242,7 +242,7 @@ public:
163
164 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
165 dynamic_reconfigure::Server<Config>::CallbackType f =
166 - boost::bind(&ConvexHullNodelet::reconfigureCallback, this, _1, _2);
167 + boost::bind(&ConvexHullNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
168 reconfigure_server_->setCallback(f);
169
170 img_pub_ = advertiseImage(*pnh_, "image", 1);
171 diff --git a/src/nodelet/corner_harris_nodelet.cpp b/src/nodelet/corner_harris_nodelet.cpp
172 index a3e89d3..6199720 100644
173 --- a/src/nodelet/corner_harris_nodelet.cpp
174 +++ b/src/nodelet/corner_harris_nodelet.cpp
175 @@ -216,7 +216,7 @@ public:
176
177 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
178 dynamic_reconfigure::Server<Config>::CallbackType f =
179 - boost::bind(&CornerHarrisNodelet::reconfigureCallback, this, _1, _2);
180 + boost::bind(&CornerHarrisNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
181 reconfigure_server_->setCallback(f);
182
183 img_pub_ = advertiseImage(*pnh_, "image", 1);
184 diff --git a/src/nodelet/discrete_fourier_transform_nodelet.cpp b/src/nodelet/discrete_fourier_transform_nodelet.cpp
185 index 3305e20..675fffe 100644
186 --- a/src/nodelet/discrete_fourier_transform_nodelet.cpp
187 +++ b/src/nodelet/discrete_fourier_transform_nodelet.cpp
188 @@ -202,7 +202,7 @@ public:
189
190 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
191 dynamic_reconfigure::Server<Config>::CallbackType f =
192 - boost::bind(&DiscreteFourierTransformNodelet::reconfigureCallback, this, _1, _2);
193 + boost::bind(&DiscreteFourierTransformNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
194 reconfigure_server_->setCallback(f);
195
196 img_pub_ = advertiseImage(*pnh_, "image", 1);
197 diff --git a/src/nodelet/edge_detection_nodelet.cpp b/src/nodelet/edge_detection_nodelet.cpp
198 index fc3ed1f..6a71f23 100644
199 --- a/src/nodelet/edge_detection_nodelet.cpp
200 +++ b/src/nodelet/edge_detection_nodelet.cpp
201 @@ -310,7 +310,7 @@ public:
202
203 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
204 dynamic_reconfigure::Server<Config>::CallbackType f =
205 - boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, _1, _2);
206 + boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
207 reconfigure_server_->setCallback(f);
208
209 img_pub_ = advertiseImage(*pnh_, "image", 1);
210 diff --git a/src/nodelet/face_detection_nodelet.cpp b/src/nodelet/face_detection_nodelet.cpp
211 index 371f6a8..6c27fda 100644
212 --- a/src/nodelet/face_detection_nodelet.cpp
213 +++ b/src/nodelet/face_detection_nodelet.cpp
214 @@ -244,7 +244,7 @@ public:
215
216 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
217 dynamic_reconfigure::Server<Config>::CallbackType f =
218 - boost::bind(&FaceDetectionNodelet::reconfigureCallback, this, _1, _2);
219 + boost::bind(&FaceDetectionNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
220 reconfigure_server_->setCallback(f);
221
222 img_pub_ = advertiseImage(*pnh_, "image", 1);
223 diff --git a/src/nodelet/face_recognition_nodelet.cpp b/src/nodelet/face_recognition_nodelet.cpp
224 index ef7b7b5..f7a2e2f 100644
225 --- a/src/nodelet/face_recognition_nodelet.cpp
226 +++ b/src/nodelet/face_recognition_nodelet.cpp
227 @@ -631,13 +631,13 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet
228 {
229 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
230 async_->connectInput(img_sub_, face_sub_);
231 - async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
232 + async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, boost::placeholders::_1, boost::placeholders::_2));
233 }
234 else
235 {
236 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
237 sync_->connectInput(img_sub_, face_sub_);
238 - sync_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
239 + sync_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, boost::placeholders::_1, boost::placeholders::_2));
240 }
241 }
242
243 @@ -658,7 +658,7 @@ public:
244
245 // dynamic reconfigures
246 cfg_srv_ = boost::make_shared<Server>(*pnh_);
247 - Server::CallbackType f = boost::bind(&FaceRecognitionNodelet::configCallback, this, _1, _2);
248 + Server::CallbackType f = boost::bind(&FaceRecognitionNodelet::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
249 cfg_srv_->setCallback(f);
250
251 // parameters
252 diff --git a/src/nodelet/fback_flow_nodelet.cpp b/src/nodelet/fback_flow_nodelet.cpp
253 index 5761ad3..5086a73 100644
254 --- a/src/nodelet/fback_flow_nodelet.cpp
255 +++ b/src/nodelet/fback_flow_nodelet.cpp
256 @@ -225,7 +225,7 @@ public:
257
258 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
259 dynamic_reconfigure::Server<Config>::CallbackType f =
260 - boost::bind(&FBackFlowNodelet::reconfigureCallback, this, _1, _2);
261 + boost::bind(&FBackFlowNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
262 reconfigure_server_->setCallback(f);
263
264 img_pub_ = advertiseImage(*pnh_, "image", 1);
265 diff --git a/src/nodelet/find_contours_nodelet.cpp b/src/nodelet/find_contours_nodelet.cpp
266 index 506320b..dc70368 100644
267 --- a/src/nodelet/find_contours_nodelet.cpp
268 +++ b/src/nodelet/find_contours_nodelet.cpp
269 @@ -237,7 +237,7 @@ public:
270
271 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
272 dynamic_reconfigure::Server<Config>::CallbackType f =
273 - boost::bind(&FindContoursNodelet::reconfigureCallback, this, _1, _2);
274 + boost::bind(&FindContoursNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
275 reconfigure_server_->setCallback(f);
276
277 img_pub_ = advertiseImage(*pnh_, "image", 1);
278 diff --git a/src/nodelet/general_contours_nodelet.cpp b/src/nodelet/general_contours_nodelet.cpp
279 index b0b7803..5d78a10 100644
280 --- a/src/nodelet/general_contours_nodelet.cpp
281 +++ b/src/nodelet/general_contours_nodelet.cpp
282 @@ -271,7 +271,7 @@ public:
283
284 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
285 dynamic_reconfigure::Server<Config>::CallbackType f =
286 - boost::bind(&GeneralContoursNodelet::reconfigureCallback, this, _1, _2);
287 + boost::bind(&GeneralContoursNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
288 reconfigure_server_->setCallback(f);
289
290 img_pub_ = advertiseImage(*pnh_, "image", 1);
291 diff --git a/src/nodelet/goodfeature_track_nodelet.cpp b/src/nodelet/goodfeature_track_nodelet.cpp
292 index 0fae783..61df7d0 100644
293 --- a/src/nodelet/goodfeature_track_nodelet.cpp
294 +++ b/src/nodelet/goodfeature_track_nodelet.cpp
295 @@ -237,7 +237,7 @@ public:
296
297 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
298 dynamic_reconfigure::Server<Config>::CallbackType f =
299 - boost::bind(&GoodfeatureTrackNodelet::reconfigureCallback, this, _1, _2);
300 + boost::bind(&GoodfeatureTrackNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
301 reconfigure_server_->setCallback(f);
302
303 img_pub_ = advertiseImage(*pnh_, "image", 1);
304 diff --git a/src/nodelet/hough_circles_nodelet.cpp b/src/nodelet/hough_circles_nodelet.cpp
305 index f834645..01f2ece 100644
306 --- a/src/nodelet/hough_circles_nodelet.cpp
307 +++ b/src/nodelet/hough_circles_nodelet.cpp
308 @@ -358,7 +358,7 @@ public:
309
310 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
311 dynamic_reconfigure::Server<Config>::CallbackType f =
312 - boost::bind(&HoughCirclesNodelet::reconfigureCallback, this, _1, _2);
313 + boost::bind(&HoughCirclesNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
314 reconfigure_server_->setCallback(f);
315
316 img_pub_ = advertiseImage(*pnh_, "image", 1);
317 diff --git a/src/nodelet/hough_lines_nodelet.cpp b/src/nodelet/hough_lines_nodelet.cpp
318 index 6e20001..2691eb9 100644
319 --- a/src/nodelet/hough_lines_nodelet.cpp
320 +++ b/src/nodelet/hough_lines_nodelet.cpp
321 @@ -304,7 +304,7 @@ public:
322
323 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
324 dynamic_reconfigure::Server<Config>::CallbackType f =
325 - boost::bind(&HoughLinesNodelet::reconfigureCallback, this, _1, _2);
326 + boost::bind(&HoughLinesNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
327 reconfigure_server_->setCallback(f);
328
329 img_pub_ = advertiseImage(*pnh_, "image", 1);
330 diff --git a/src/nodelet/lk_flow_nodelet.cpp b/src/nodelet/lk_flow_nodelet.cpp
331 index 867b804..37d01dc 100644
332 --- a/src/nodelet/lk_flow_nodelet.cpp
333 +++ b/src/nodelet/lk_flow_nodelet.cpp
334 @@ -332,7 +332,7 @@ public:
335
336 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
337 dynamic_reconfigure::Server<Config>::CallbackType f =
338 - boost::bind(&LKFlowNodelet::reconfigureCallback, this, _1, _2);
339 + boost::bind(&LKFlowNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
340 reconfigure_server_->setCallback(f);
341
342 img_pub_ = advertiseImage(*pnh_, "image", 1);
343 diff --git a/src/nodelet/people_detect_nodelet.cpp b/src/nodelet/people_detect_nodelet.cpp
344 index ce94e2d..ddc4d3e 100644
345 --- a/src/nodelet/people_detect_nodelet.cpp
346 +++ b/src/nodelet/people_detect_nodelet.cpp
347 @@ -226,7 +226,7 @@ public:
348
349 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
350 dynamic_reconfigure::Server<Config>::CallbackType f =
351 - boost::bind(&PeopleDetectNodelet::reconfigureCallback, this, _1, _2);
352 + boost::bind(&PeopleDetectNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
353 reconfigure_server_->setCallback(f);
354
355 hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
356 diff --git a/src/nodelet/phase_corr_nodelet.cpp b/src/nodelet/phase_corr_nodelet.cpp
357 index df2f2c1..9bd2f9e 100644
358 --- a/src/nodelet/phase_corr_nodelet.cpp
359 +++ b/src/nodelet/phase_corr_nodelet.cpp
360 @@ -218,7 +218,7 @@ public:
361
362 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
363 dynamic_reconfigure::Server<Config>::CallbackType f =
364 - boost::bind(&PhaseCorrNodelet::reconfigureCallback, this, _1, _2);
365 + boost::bind(&PhaseCorrNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
366 reconfigure_server_->setCallback(f);
367
368 img_pub_ = advertiseImage(*pnh_, "image", 1);
369 diff --git a/src/nodelet/pyramids_nodelet.cpp b/src/nodelet/pyramids_nodelet.cpp
370 index 469f48b..0a7428f 100644
371 --- a/src/nodelet/pyramids_nodelet.cpp
372 +++ b/src/nodelet/pyramids_nodelet.cpp
373 @@ -182,7 +182,7 @@ public:
374
375 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
376 dynamic_reconfigure::Server<Config>::CallbackType f =
377 - boost::bind(&PyramidsNodelet::reconfigureCallback, this, _1, _2);
378 + boost::bind(&PyramidsNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
379 reconfigure_server_->setCallback(f);
380
381 img_pub_ = advertiseImage(*pnh_, "image", 1);
382 diff --git a/src/nodelet/segment_objects_nodelet.cpp b/src/nodelet/segment_objects_nodelet.cpp
383 index 609de52..54b6d28 100644
384 --- a/src/nodelet/segment_objects_nodelet.cpp
385 +++ b/src/nodelet/segment_objects_nodelet.cpp
386 @@ -276,7 +276,7 @@ public:
387
388 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
389 dynamic_reconfigure::Server<Config>::CallbackType f =
390 - boost::bind(&SegmentObjectsNodelet::reconfigureCallback, this, _1, _2);
391 + boost::bind(&SegmentObjectsNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
392 reconfigure_server_->setCallback(f);
393
394 img_pub_ = advertiseImage(*pnh_, "image", 1);
395 diff --git a/src/nodelet/simple_flow_nodelet.cpp b/src/nodelet/simple_flow_nodelet.cpp
396 index 300563a..35d299e 100644
397 --- a/src/nodelet/simple_flow_nodelet.cpp
398 +++ b/src/nodelet/simple_flow_nodelet.cpp
399 @@ -259,7 +259,7 @@ public:
400
401 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
402 dynamic_reconfigure::Server<Config>::CallbackType f =
403 - boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, _1, _2);
404 + boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
405 reconfigure_server_->setCallback(f);
406
407 img_pub_ = advertiseImage(*pnh_, "image", 1);
408 diff --git a/src/nodelet/smoothing_nodelet.cpp b/src/nodelet/smoothing_nodelet.cpp
409 index 6d6bff8..14bfefe 100644
410 --- a/src/nodelet/smoothing_nodelet.cpp
411 +++ b/src/nodelet/smoothing_nodelet.cpp
412 @@ -224,7 +224,7 @@ public:
413
414 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
415 dynamic_reconfigure::Server<Config>::CallbackType f =
416 - boost::bind(&SmoothingNodelet::reconfigureCallback, this, _1, _2);
417 + boost::bind(&SmoothingNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
418 reconfigure_server_->setCallback(f);
419
420 img_pub_ = advertiseImage(*pnh_, "image", 1);
421 diff --git a/src/nodelet/threshold_nodelet.cpp b/src/nodelet/threshold_nodelet.cpp
422 index 79fabf7..87a8748 100644
423 --- a/src/nodelet/threshold_nodelet.cpp
424 +++ b/src/nodelet/threshold_nodelet.cpp
425 @@ -163,7 +163,7 @@ public:
426 ////////////////////////////////////////////////////////
427 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
428 dynamic_reconfigure::Server<Config>::CallbackType f =
429 - boost::bind(&ThresholdNodelet::reconfigureCallback, this, _1, _2);
430 + boost::bind(&ThresholdNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
431 reconfigure_server_->setCallback(f);
432
433 img_pub_ = advertiseImage(*pnh_, "image", 1);
434 diff --git a/src/nodelet/watershed_segmentation_nodelet.cpp b/src/nodelet/watershed_segmentation_nodelet.cpp
435 index efde9a6..bce16b8 100644
436 --- a/src/nodelet/watershed_segmentation_nodelet.cpp
437 +++ b/src/nodelet/watershed_segmentation_nodelet.cpp
438 @@ -331,7 +331,7 @@ public:
439
440 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
441 dynamic_reconfigure::Server<Config>::CallbackType f =
442 - boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2);
443 + boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
444 reconfigure_server_->setCallback(f);
445
446 add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::addSeedPointCb, this);
00 0001-Add-Debian-specific-SOVERSION.patch
11 0003-Switch-to-Python-3.patch
2 0003-Switch-to-new-boost-bind-bind.hpp.patch