Codebase list ros-actionlib / 4fbbdc9
Add patch for Boost 1.74 Jochen Sprickerhof 3 years ago
2 changed file(s) with 308 addition(s) and 0 deletion(s). Raw diff Collapse all Expand all
0 From: Jochen Sprickerhof <git@jochen.sprickerhof.de>
1 Date: Mon, 14 Dec 2020 11:18:40 +0100
2 Subject: Switch to new boost/bind/bind.hpp
3
4 ---
5 actionlib/include/actionlib/client/action_client.h | 14 ++++++-------
6 .../include/actionlib/client/goal_manager_imp.h | 2 +-
7 .../actionlib/client/simple_action_client.h | 4 ++--
8 actionlib/include/actionlib/managed_list.h | 2 +-
9 actionlib/include/actionlib/one_shot_timer.h | 4 ++--
10 .../include/actionlib/server/action_server_imp.h | 6 +++---
11 .../include/actionlib/server/service_server_imp.h | 2 +-
12 .../actionlib/server/simple_action_server_imp.h | 24 +++++++++++-----------
13 actionlib/test/add_two_ints_server.cpp | 2 +-
14 actionlib/test/destruction_guard_test.cpp | 2 +-
15 actionlib/test/ref_server.cpp | 4 ++--
16 actionlib/test/server_goal_handle_destruction.cpp | 2 +-
17 actionlib/test/simple_client_test.cpp | 2 +-
18 actionlib/test/simple_execute_ref_server.cpp | 2 +-
19 14 files changed, 36 insertions(+), 36 deletions(-)
20
21 diff --git a/actionlib/include/actionlib/client/action_client.h b/actionlib/include/actionlib/client/action_client.h
22 index cfd64af..cb79ae2 100644
23 --- a/actionlib/include/actionlib/client/action_client.h
24 +++ b/actionlib/include/actionlib/client/action_client.h
25 @@ -236,17 +236,17 @@ private:
26
27 // Start publishers and subscribers
28 goal_pub_ = queue_advertise<ActionGoal>("goal", static_cast<uint32_t>(pub_queue_size),
29 - boost::bind(&ConnectionMonitor::goalConnectCallback, connection_monitor_, _1),
30 - boost::bind(&ConnectionMonitor::goalDisconnectCallback, connection_monitor_, _1),
31 + boost::bind(&ConnectionMonitor::goalConnectCallback, connection_monitor_, boost::placeholders::_1),
32 + boost::bind(&ConnectionMonitor::goalDisconnectCallback, connection_monitor_, boost::placeholders::_1),
33 queue);
34 cancel_pub_ =
35 queue_advertise<actionlib_msgs::GoalID>("cancel", static_cast<uint32_t>(pub_queue_size),
36 - boost::bind(&ConnectionMonitor::cancelConnectCallback, connection_monitor_, _1),
37 - boost::bind(&ConnectionMonitor::cancelDisconnectCallback, connection_monitor_, _1),
38 + boost::bind(&ConnectionMonitor::cancelConnectCallback, connection_monitor_, boost::placeholders::_1),
39 + boost::bind(&ConnectionMonitor::cancelDisconnectCallback, connection_monitor_, boost::placeholders::_1),
40 queue);
41
42 - manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, _1));
43 - manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, _1));
44 + manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, boost::placeholders::_1));
45 + manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, boost::placeholders::_1));
46 }
47
48 template<class M>
49 @@ -275,7 +275,7 @@ private:
50 ops.datatype = ros::message_traits::datatype<M>();
51 ops.helper = ros::SubscriptionCallbackHelperPtr(
52 new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<M const> &>(
53 - boost::bind(fp, obj, _1)
54 + boost::bind(fp, obj, boost::placeholders::_1)
55 )
56 );
57 return n_.subscribe(ops);
58 diff --git a/actionlib/include/actionlib/client/goal_manager_imp.h b/actionlib/include/actionlib/client/goal_manager_imp.h
59 index 789ada0..30dbc35 100644
60 --- a/actionlib/include/actionlib/client/goal_manager_imp.h
61 +++ b/actionlib/include/actionlib/client/goal_manager_imp.h
62 @@ -74,7 +74,7 @@ ClientGoalHandle<ActionSpec> GoalManager<ActionSpec>::initGoal(const Goal & goal
63
64 boost::recursive_mutex::scoped_lock lock(list_mutex_);
65 typename ManagedListT::Handle list_handle =
66 - list_.add(comm_state_machine, boost::bind(&GoalManagerT::listElemDeleter, this, _1), guard_);
67 + list_.add(comm_state_machine, boost::bind(&GoalManagerT::listElemDeleter, this, boost::placeholders::_1), guard_);
68
69 if (send_goal_func_) {
70 send_goal_func_(action_goal);
71 diff --git a/actionlib/include/actionlib/client/simple_action_client.h b/actionlib/include/actionlib/client/simple_action_client.h
72 index 52637ed..cfbd206 100644
73 --- a/actionlib/include/actionlib/client/simple_action_client.h
74 +++ b/actionlib/include/actionlib/client/simple_action_client.h
75 @@ -330,8 +330,8 @@ void SimpleActionClient<ActionSpec>::sendGoal(const Goal & goal,
76 cur_simple_state_ = SimpleGoalState::PENDING;
77
78 // Send the goal to the ActionServer
79 - gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition, this, _1),
80 - boost::bind(&SimpleActionClientT::handleFeedback, this, _1, _2));
81 + gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition, this, boost::placeholders::_1),
82 + boost::bind(&SimpleActionClientT::handleFeedback, this, boost::placeholders::_1, boost::placeholders::_2));
83 }
84
85 template<class ActionSpec>
86 diff --git a/actionlib/include/actionlib/managed_list.h b/actionlib/include/actionlib/managed_list.h
87 index 11c4889..b7f9231 100644
88 --- a/actionlib/include/actionlib/managed_list.h
89 +++ b/actionlib/include/actionlib/managed_list.h
90 @@ -218,7 +218,7 @@ private:
91 */
92 Handle add(const T & elem)
93 {
94 - return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, _1) );
95 + return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, boost::placeholders::_1) );
96 }
97
98 /**
99 diff --git a/actionlib/include/actionlib/one_shot_timer.h b/actionlib/include/actionlib/one_shot_timer.h
100 index e462abb..55d19bb 100644
101 --- a/actionlib/include/actionlib/one_shot_timer.h
102 +++ b/actionlib/include/actionlib/one_shot_timer.h
103 @@ -36,7 +36,7 @@
104 #define ACTIONLIB__ONE_SHOT_TIMER_H_
105
106 #include "ros/ros.h"
107 -#include "boost/bind.hpp"
108 +#include "boost/bind/bind.hpp"
109
110 //! Horrible hack until ROS Supports this (ROS Trac #1387)
111 class OneShotTimer
112 @@ -60,7 +60,7 @@ public:
113
114 boost::function<void(const ros::TimerEvent & e)> getCb()
115 {
116 - return boost::bind(&OneShotTimer::cb, this, _1);
117 + return boost::bind(&OneShotTimer::cb, this, boost::placeholders::_1);
118 }
119
120 void registerOneShotCb(boost::function<void(const ros::TimerEvent & e)> callback)
121 diff --git a/actionlib/include/actionlib/server/action_server_imp.h b/actionlib/include/actionlib/server/action_server_imp.h
122 index 2a088b1..837b9c4 100644
123 --- a/actionlib/include/actionlib/server/action_server_imp.h
124 +++ b/actionlib/include/actionlib/server/action_server_imp.h
125 @@ -172,15 +172,15 @@ void ActionServer<ActionSpec>::initialize()
126
127 if (status_frequency > 0) {
128 status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency),
129 - boost::bind(&ActionServer::publishStatus, this, _1));
130 + boost::bind(&ActionServer::publishStatus, this, boost::placeholders::_1));
131 }
132
133 goal_sub_ = node_.subscribe<ActionGoal>("goal", static_cast<uint32_t>(sub_queue_size),
134 - boost::bind(&ActionServerBase<ActionSpec>::goalCallback, this, _1));
135 + boost::bind(&ActionServerBase<ActionSpec>::goalCallback, this, boost::placeholders::_1));
136
137 cancel_sub_ =
138 node_.subscribe<actionlib_msgs::GoalID>("cancel", static_cast<uint32_t>(sub_queue_size),
139 - boost::bind(&ActionServerBase<ActionSpec>::cancelCallback, this, _1));
140 + boost::bind(&ActionServerBase<ActionSpec>::cancelCallback, this, boost::placeholders::_1));
141 }
142
143 template<class ActionSpec>
144 diff --git a/actionlib/include/actionlib/server/service_server_imp.h b/actionlib/include/actionlib/server/service_server_imp.h
145 index ac5444d..2f0265e 100644
146 --- a/actionlib/include/actionlib/server/service_server_imp.h
147 +++ b/actionlib/include/actionlib/server/service_server_imp.h
148 @@ -58,7 +58,7 @@ ServiceServerImpT<ActionSpec>::ServiceServerImpT(ros::NodeHandle n, std::string
149 : service_cb_(service_cb)
150 {
151 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
152 - boost::bind(&ServiceServerImpT::goalCB, this, _1), false));
153 + boost::bind(&ServiceServerImpT::goalCB, this, boost::placeholders::_1), false));
154 as_->start();
155 }
156
157 diff --git a/actionlib/include/actionlib/server/simple_action_server_imp.h b/actionlib/include/actionlib/server/simple_action_server_imp.h
158 index a5e51bb..d8b906a 100644
159 --- a/actionlib/include/actionlib/server/simple_action_server_imp.h
160 +++ b/actionlib/include/actionlib/server/simple_action_server_imp.h
161 @@ -56,8 +56,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name,
162
163 // create the action server
164 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
165 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
166 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
167 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
168 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
169 auto_start));
170 }
171
172 @@ -68,8 +68,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name, bool auto_s
173 {
174 // create the action server
175 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
176 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
177 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
178 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
179 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
180 auto_start));
181
182 if (execute_callback_ != NULL) {
183 @@ -85,8 +85,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name,
184 {
185 // create the action server
186 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
187 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
188 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
189 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
190 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
191 true));
192
193 if (execute_callback_ != NULL) {
194 @@ -104,8 +104,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
195 {
196 // create the action server
197 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
198 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
199 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
200 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
201 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
202 auto_start));
203
204 if (execute_callback_ != NULL) {
205 @@ -121,8 +121,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
206 {
207 // create the action server
208 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
209 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
210 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
211 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
212 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
213 auto_start));
214
215 if (execute_callback_ != NULL) {
216 @@ -138,8 +138,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
217 {
218 // create the action server
219 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
220 - boost::bind(&SimpleActionServer::goalCallback, this, _1),
221 - boost::bind(&SimpleActionServer::preemptCallback, this, _1),
222 + boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
223 + boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
224 true));
225
226 if (execute_callback_ != NULL) {
227 diff --git a/actionlib/test/add_two_ints_server.cpp b/actionlib/test/add_two_ints_server.cpp
228 index 098c315..84ddace 100644
229 --- a/actionlib/test/add_two_ints_server.cpp
230 +++ b/actionlib/test/add_two_ints_server.cpp
231 @@ -53,7 +53,7 @@ int main(int argc, char ** argv)
232
233 actionlib::ServiceServer service = actionlib::advertiseService<actionlib::TwoIntsAction>(n,
234 "add_two_ints",
235 - boost::bind(add, _1, _2));
236 + boost::bind(add, boost::placeholders::_1, boost::placeholders::_2));
237
238 ros::spin();
239
240 diff --git a/actionlib/test/destruction_guard_test.cpp b/actionlib/test/destruction_guard_test.cpp
241 index a497124..5473b1d 100644
242 --- a/actionlib/test/destruction_guard_test.cpp
243 +++ b/actionlib/test/destruction_guard_test.cpp
244 @@ -37,7 +37,7 @@
245 #include <gtest/gtest.h>
246 #include <actionlib/destruction_guard.h>
247 #include <boost/thread.hpp>
248 -#include <boost/bind.hpp>
249 +#include <boost/bind/bind.hpp>
250
251 using namespace actionlib;
252
253 diff --git a/actionlib/test/ref_server.cpp b/actionlib/test/ref_server.cpp
254 index 1da0ab5..7aede23 100644
255 --- a/actionlib/test/ref_server.cpp
256 +++ b/actionlib/test/ref_server.cpp
257 @@ -61,8 +61,8 @@ using namespace actionlib;
258
259 RefServer::RefServer(ros::NodeHandle & n, const std::string & name)
260 : ActionServer<TestAction>(n, name,
261 - boost::bind(&RefServer::goalCallback, this, _1),
262 - boost::bind(&RefServer::cancelCallback, this, _1),
263 + boost::bind(&RefServer::goalCallback, this, boost::placeholders::_1),
264 + boost::bind(&RefServer::cancelCallback, this, boost::placeholders::_1),
265 false)
266 {
267 start();
268 diff --git a/actionlib/test/server_goal_handle_destruction.cpp b/actionlib/test/server_goal_handle_destruction.cpp
269 index 9e179c7..ed12d2b 100644
270 --- a/actionlib/test/server_goal_handle_destruction.cpp
271 +++ b/actionlib/test/server_goal_handle_destruction.cpp
272 @@ -67,7 +67,7 @@ ServerGoalHandleDestructionTester::ServerGoalHandleDestructionTester()
273 as_ = new ActionServer<TestAction>(nh_, "reference_action", false);
274 as_->start();
275 as_->registerGoalCallback(boost::bind(&ServerGoalHandleDestructionTester::goalCallback, this,
276 - _1));
277 + boost::placeholders::_1));
278 gh_ = new GoalHandle();
279 }
280
281 diff --git a/actionlib/test/simple_client_test.cpp b/actionlib/test/simple_client_test.cpp
282 index 341bbc9..ea40050 100644
283 --- a/actionlib/test/simple_client_test.cpp
284 +++ b/actionlib/test/simple_client_test.cpp
285 @@ -106,7 +106,7 @@ TEST(SimpleClient, easy_callback)
286
287 bool called = false;
288 goal.goal = 1;
289 - SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, _1, _2);
290 + SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, boost::placeholders::_1, boost::placeholders::_2);
291 client.sendGoal(goal, func);
292 finished = client.waitForResult(ros::Duration(10.0));
293 ASSERT_TRUE(finished);
294 diff --git a/actionlib/test/simple_execute_ref_server.cpp b/actionlib/test/simple_execute_ref_server.cpp
295 index 57aa9cd..b663ec4 100644
296 --- a/actionlib/test/simple_execute_ref_server.cpp
297 +++ b/actionlib/test/simple_execute_ref_server.cpp
298 @@ -61,7 +61,7 @@ using namespace actionlib;
299
300 SimpleExecuteRefServer::SimpleExecuteRefServer()
301 : as_(nh_, "reference_action", boost::bind(&SimpleExecuteRefServer::executeCallback, this,
302 - _1), false)
303 + boost::placeholders::_1), false)
304 {
305 as_.start();
306 }
11 0003-Switch-to-Python-3.patch
22 0003-Add-CMakeLists.txt.patch
33 0004-Disable-flaky-test.patch
4 0005-Switch-to-new-boost-bind-bind.hpp.patch