29 #ifndef SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_ 30 #define SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_ 34 #include <boost/thread/mutex.hpp> 41 template<
class MReq,
class MRes>
64 const std::string &service,
65 const std::string &client_name =
"")
69 service_name_ = rservice;
71 request_pub_ = nh.
advertise<MReq>(rservice +
"/request", 10);
75 bool call(MReq& request, MRes& response)
77 boost::mutex::scoped_lock scoped_lock(request_lock_);
82 request.srv_header.sender =
name_;
98 while (!response_ &&
ros::Time::now() - request.srv_header.stamp < timeout_)
109 return response.srv_header.result;
132 ROS_DEBUG(
"Got response for %s with sequence %i",
133 message->srv_header.sender.c_str(), message->srv_header.sequence);
135 if (message->srv_header.sender != name_)
137 ROS_DEBUG(
"Got response from another client, ignoring..");
141 if (message->srv_header.sequence != sequence_)
143 ROS_WARN(
"Got wrong sequence number, ignoring..");
164 #endif // SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
void publish(const boost::shared_ptr< M > &message) const
void response_callback(const boost::shared_ptr< MRes > &message)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(MReq &request, MRes &response)
ros::Subscriber response_sub_
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL const std::string & getName()
boost::shared_ptr< MRes > response_
ros::Publisher request_pub_
void initialize(ros::NodeHandle &nh, const std::string &service, const std::string &client_name="")
uint32_t getNumPublishers() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string service_name_
uint32_t getNumSubscribers() const
void setLogCalls(bool enable)
boost::mutex request_lock_
ROSCPP_DECL void spinOnce()