Go to the documentation of this file.
29 #ifndef SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
30 #define SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
45 template<
class MReq,
class MRes,
class T>
56 const std::string &service,
57 bool(T::*srv_func)(
const MReq &, MRes &),
75 ROS_DEBUG(
"Got request from %s with sequence %i", message.srv_header.sender.c_str(), message.srv_header.sequence);
81 response.srv_header.sequence = message.srv_header.sequence;
82 response.srv_header.sender = message.srv_header.sender;
96 template<
class MReq,
class MRes,
class T>
98 const std::string &service,
99 bool(T::*srv_func)(
const MReq &, MRes &),
109 template<
class MReq,
class MRes,
class T>
112 const std::string &service,
113 bool(T::*srv_func)(
const MReq &, MRes &),
122 #endif // SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
const std::string response
ros::Subscriber request_sub_
void initialize(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const MReq &, MRes &), T *obj)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::string resolveName(const std::string &name, bool remap=true) const
boost::shared_ptr< ImplRoot > impl_
ros::Publisher response_pub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void request_callback(const MReq &message)
void initialize(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const MReq &, MRes &), T *obj)
bool(T::* callback_)(const MReq &, MRes &)
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15