29 #ifndef SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_
30 #define SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_
35 #include <boost/thread/mutex.hpp>
36 #include <boost/uuid/random_generator.hpp>
37 #include <boost/uuid/uuid_io.hpp>
43 template<
class MReq,
class MRes>
65 const std::string &service,
66 const std::string &client_name =
"")
69 boost::uuids::random_generator gen;
70 boost::uuids::uuid u = gen();
71 std::string random_str = boost::uuids::to_string(u);
80 bool call(MReq& request, MRes& response)
87 request.srv_header.sender =
name_;
97 ROS_ERROR(
"Topic service timeout exceeded");
125 ROS_DEBUG(
"Got response for %s with sequence %i",
126 message->srv_header.sender.c_str(), message->srv_header.sequence);
128 if (message->srv_header.sender !=
name_)
130 ROS_DEBUG(
"Got response from another client, ignoring..");
134 if (message->srv_header.sequence !=
sequence_)
136 ROS_WARN(
"Got wrong sequence number, ignoring..");
137 ROS_DEBUG(
"message seq:%i vs current seq: %i", message->srv_header.sequence,
sequence_);
153 const std::string &service,
154 const std::string &client_name =
"")
159 impl_->initialize(nh, service, client_name);
164 return impl_->service_name_;
169 return impl_->request_pub_.getNumSubscribers() > 0 &&
impl_->response_sub_.getNumPublishers() > 0;
174 return impl_->call(req.request, req.response);
180 #endif // SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_