mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
service_client_handler.hpp
1 #ifndef SERVICE_CLIENT_HANDLER_HPP
2 #define SERVICE_CLIENT_HANDLER_HPP
3 
4 namespace mrs_lib
5 {
6 
7 // --------------------------------------------------------------
8 // | ServiceClientHandler_impl |
9 // --------------------------------------------------------------
10 
11 /* ServiceClientHandler_impl(void) //{ */
12 
13 template <class ServiceType>
15 }
16 
17 //}
18 
19 /* ServiceClientHandler_impl(ros::NodeHandle& nh, const std::string& address) //{ */
20 
21 template <class ServiceType>
22 ServiceClientHandler_impl<ServiceType>::ServiceClientHandler_impl(ros::NodeHandle& nh, const std::string& address) {
23 
24  {
25  std::scoped_lock lock(mutex_service_client_);
26 
27  service_client_ = nh.serviceClient<ServiceType>(address);
28  }
29 
30  _address_ = address;
31  async_attempts_ = 1;
32 
33  /* thread_oneshot_ = std::make_shared<std::thread>(std::thread(&ServiceClientHandler_impl::threadOneshot, this, true, false)); */
34 
35  service_initialized_ = true;
36 }
37 
38 //}
39 
40 /* call(ServiceType& srv) //{ */
41 
42 template <class ServiceType>
44 
45  if (!service_initialized_) {
46  return false;
47  }
48 
49  return service_client_.call(srv);
50 }
51 
52 //}
53 
54 /* call(ServiceType& srv, const int& attempts) //{ */
55 
56 template <class ServiceType>
57 bool ServiceClientHandler_impl<ServiceType>::call(ServiceType& srv, const int& attempts) {
58 
59  if (!service_initialized_) {
60  return false;
61  }
62 
63  std::scoped_lock lock(mutex_service_client_);
64 
65  bool success = false;
66  int counter = 0;
67 
68  while (!success && ros::ok()) {
69 
70  success = service_client_.call(srv);
71 
72  if (!success) {
73  ROS_ERROR("[%s]: failed to call service to '%s'", ros::this_node::getName().c_str(), _address_.c_str());
74  }
75 
76  if (++counter >= attempts) {
77  break;
78  }
79  }
80 
81  return success;
82 }
83 
84 //}
85 
86 /* call(ServiceType& srv, const int& attempts, const double& repeat_delay) //{ */
87 
88 template <class ServiceType>
89 bool ServiceClientHandler_impl<ServiceType>::call(ServiceType& srv, const int& attempts, const double& repeat_delay) {
90 
91  if (!service_initialized_) {
92  return false;
93  }
94 
95  std::scoped_lock lock(mutex_service_client_);
96 
97  bool success = false;
98  int counter = 0;
99 
100  while (!success && ros::ok()) {
101 
102  success = service_client_.call(srv);
103 
104  if (!success) {
105  ROS_ERROR("[%s]: failed to call service to '%s'", ros::this_node::getName().c_str(), _address_.c_str());
106  }
107 
108  if (++counter >= attempts) {
109  break;
110  }
111 
112  ros::Duration(repeat_delay).sleep();
113  }
114 
115  return success;
116 }
117 
118 //}
119 
120 /* callAsync(ServiceType& srv) //{ */
121 
122 template <class ServiceType>
123 std::future<ServiceType> ServiceClientHandler_impl<ServiceType>::callAsync(ServiceType& srv) {
124 
125  {
126  std::scoped_lock lock(mutex_async_);
127 
128  async_data_ = srv;
129  async_attempts_ = 1;
130  async_repeat_delay_ = 0;
131  }
132 
133  return std::async(std::launch::async, &ServiceClientHandler_impl::asyncRun, this);
134 }
135 
136 //}
137 
138 /* callAsync(ServiceType& srv, const int& attempts) //{ */
139 
140 template <class ServiceType>
141 std::future<ServiceType> ServiceClientHandler_impl<ServiceType>::callAsync(ServiceType& srv, const int& attempts) {
142 
143  {
144  std::scoped_lock lock(mutex_async_);
145 
146  async_data_ = srv;
147  async_attempts_ = attempts;
148  async_repeat_delay_ = 0;
149  }
150 
151  return std::async(std::launch::async, &ServiceClientHandler_impl::asyncRun, this);
152 }
153 
154 //}
155 
156 /* callAsync(ServiceType& srv, const int& attempts, const double &repeat_delay) //{ */
157 
158 template <class ServiceType>
159 std::future<ServiceType> ServiceClientHandler_impl<ServiceType>::callAsync(ServiceType& srv, const int& attempts, const double& repeat_delay) {
160 
161  {
162  std::scoped_lock lock(mutex_async_);
163 
164  async_data_ = srv;
165  async_attempts_ = attempts;
166  async_repeat_delay_ = repeat_delay;
167  }
168 
169  return std::async(std::launch::async, &ServiceClientHandler_impl::asyncRun, this);
170 }
171 
172 //}
173 
174 /* asyncRun(void) //{ */
175 
176 template <class ServiceType>
178 
179  ServiceType async_data;
180  int async_attempts;
181 
182  {
183  std::scoped_lock lock(mutex_async_);
184 
185  async_data = async_data_;
186  async_attempts = async_attempts_;
187  async_repeat_delay_ = async_repeat_delay_;
188  }
189 
190  call(async_data, async_attempts, async_repeat_delay_);
191 
192  return async_data;
193 }
194 
195 //}
196 
197 // --------------------------------------------------------------
198 // | ServiceClientHandler |
199 // --------------------------------------------------------------
200 
201 /* operator= //{ */
202 
203 template <class ServiceType>
205 
206  if (this == &other) {
207  return *this;
208  }
209 
210  if (other.impl_) {
211  this->impl_ = other.impl_;
212  }
213 
214  return *this;
215 }
216 
217 //}
218 
219 /* copy constructor //{ */
220 
221 template <class ServiceType>
223 
224  if (other.impl_) {
225  this->impl_ = other.impl_;
226  }
227 }
228 
229 //}
230 
231 /* ServiceClientHandler(ros::NodeHandle& nh, const std::string& address) //{ */
232 
233 template <class ServiceType>
234 ServiceClientHandler<ServiceType>::ServiceClientHandler(ros::NodeHandle& nh, const std::string& address) {
235 
236  impl_ = std::make_shared<ServiceClientHandler_impl<ServiceType>>(nh, address);
237 }
238 
239 //}
240 
241 /* initialize(ros::NodeHandle& nh, const std::string& address) //{ */
242 
243 template <class ServiceType>
244 void ServiceClientHandler<ServiceType>::initialize(ros::NodeHandle& nh, const std::string& address) {
245 
246  impl_ = std::make_shared<ServiceClientHandler_impl<ServiceType>>(nh, address);
247 }
248 
249 //}
250 
251 /* call(ServiceType& srv) //{ */
252 
253 template <class ServiceType>
255 
256  return impl_->call(srv);
257 }
258 
259 //}
260 
261 /* call(ServiceType& srv, const int& attempts) //{ */
262 
263 template <class ServiceType>
264 bool ServiceClientHandler<ServiceType>::call(ServiceType& srv, const int& attempts) {
265 
266  return impl_->call(srv, attempts);
267 }
268 
269 //}
270 
271 /* call(ServiceType& srv, const int& attempts, const double& repeat_delay) //{ */
272 
273 template <class ServiceType>
274 bool ServiceClientHandler<ServiceType>::call(ServiceType& srv, const int& attempts, const double& repeat_delay) {
275 
276  return impl_->call(srv, attempts, repeat_delay);
277 }
278 
279 //}
280 
281 /* callAsync(ServiceType& srv) //{ */
282 
283 template <class ServiceType>
284 std::future<ServiceType> ServiceClientHandler<ServiceType>::callAsync(ServiceType& srv) {
285 
286  std::future<ServiceType> res = impl_->callAsync(srv);
287 
288  return res;
289 }
290 
291 //}
292 
293 /* callAsync(ServiceType& srv, const int& attempts) //{ */
294 
295 template <class ServiceType>
296 std::future<ServiceType> ServiceClientHandler<ServiceType>::callAsync(ServiceType& srv, const int& attempts) {
297 
298  std::future<ServiceType> res = impl_->callAsync(srv, attempts);
299 
300  return res;
301 }
302 
303 //}
304 
305 /* callAsync(ServiceType& srv, const int& attempts, const double& repeat_delay) //{ */
306 
307 template <class ServiceType>
308 std::future<ServiceType> ServiceClientHandler<ServiceType>::callAsync(ServiceType& srv, const int& attempts, const double& repeat_delay) {
309 
310  std::future<ServiceType> res = impl_->callAsync(srv, attempts, repeat_delay);
311 
312  return res;
313 }
314 
315 //}
316 
317 } // namespace mrs_lib
318 
319 #endif // SERVICE_CLIENT_HANDLER_HPP
mrs_lib::ServiceClientHandler
user wrapper of the service client handler implementation
Definition: service_client_handler.h:128
mrs_lib::ServiceClientHandler_impl
implementation of the service client handler
Definition: service_client_handler.h:24
mrs_lib::ServiceClientHandler_impl::ServiceClientHandler_impl
ServiceClientHandler_impl(void)
default constructor
Definition: service_client_handler.hpp:14
mrs_lib::ServiceClientHandler::ServiceClientHandler
ServiceClientHandler(void)
generic constructor
Definition: service_client_handler.h:134
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::ServiceClientHandler::callAsync
std::future< ServiceType > callAsync(ServiceType &srv)
asynchronous call
Definition: service_client_handler.hpp:284
mrs_lib::ServiceClientHandler_impl::callAsync
std::future< ServiceType > callAsync(ServiceType &srv)
asynchronous service call
Definition: service_client_handler.hpp:123
mrs_lib::ServiceClientHandler::initialize
void initialize(ros::NodeHandle &nh, const std::string &address)
initializer
Definition: service_client_handler.hpp:244
mrs_lib::ServiceClientHandler_impl::call
bool call(ServiceType &srv)
"classic" synchronous service call
Definition: service_client_handler.hpp:43
mrs_lib::ServiceClientHandler::call
bool call(ServiceType &srv)
"standard" synchronous call
Definition: service_client_handler.hpp:254
mrs_lib::ServiceClientHandler::operator=
ServiceClientHandler & operator=(const ServiceClientHandler &other)
operator=
Definition: service_client_handler.hpp:204