topic_service_server.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2018, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 #ifndef SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
30 #define SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
31 
32 #include <ros/node_handle.h>
33 
34 namespace swri
35 {
36 class ImplRoot
37 {
38 public:
39  virtual ~ImplRoot()
40  {
41 
42  }
43 };
44 
45 template<class MReq, class MRes, class T>
47 {
50 
51  bool(T::*callback_)(const MReq &, MRes &);
52  T* obj_;
53 
54 public:
56  const std::string &service,
57  bool(T::*srv_func)(const MReq &, MRes &),
58  T *obj)
59  {
60  callback_ = srv_func;
61  obj_ = obj;
62 
63  ros::NodeHandle pnh("~");
64 
65  std::string rservice = nh.resolveName(service);
66 
67  response_pub_ = nh.advertise<MRes>(rservice + "/response", 10);
69  }
70 
71 private:
72 
73  void request_callback(const MReq& message)
74  {
75  ROS_DEBUG("Got request from %s with sequence %i", message.srv_header.sender.c_str(), message.srv_header.sequence);
76 
77  MRes response;
78 
79  bool result = (obj_->*callback_)(message, response);
80  response.srv_header.result = result;
81  response.srv_header.sequence = message.srv_header.sequence;
82  response.srv_header.sender = message.srv_header.sender;
84  }
85 };
86 
88 {
89  private:
90 
92 
93  public:
95 
96  template<class MReq, class MRes, class T>
97  void initialize(ros::NodeHandle &nh,
98  const std::string &service,
99  bool(T::*srv_func)(const MReq &, MRes &),
100  T *obj);
101 }; // class TopicServiceServer
102 
103 inline
105 {
106 
107 }
108 
109 template<class MReq, class MRes, class T>
110 inline
112  const std::string &service,
113  bool(T::*srv_func)(const MReq &, MRes &),
114  T *obj)
115 {
117  impl->initialize(nh, service, srv_func, obj);
119 }
120 
121 } // namespace swri
122 #endif // SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
response
const std::string response
node_handle.h
ros::Publisher
boost::shared_ptr
swri::TopicServiceServerImpl::request_sub_
ros::Subscriber request_sub_
Definition: topic_service_server.h:48
swri::TopicServiceServer::initialize
void initialize(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const MReq &, MRes &), T *obj)
Definition: topic_service_server.h:111
swri::ImplRoot
Definition: topic_service_server.h:36
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
swri::TopicServiceServerImpl
Definition: topic_service_server.h:46
ROS_DEBUG
#define ROS_DEBUG(...)
swri::TopicServiceServer::impl_
boost::shared_ptr< ImplRoot > impl_
Definition: topic_service_server.h:91
swri::TopicServiceServerImpl::response_pub_
ros::Publisher response_pub_
Definition: topic_service_server.h:49
ros::NodeHandle::subscribe
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())
swri::TopicServiceServer::TopicServiceServer
TopicServiceServer()
Definition: topic_service_server.h:104
swri::TopicServiceServer
Definition: topic_service_server.h:87
swri::TopicServiceServerImpl::request_callback
void request_callback(const MReq &message)
Definition: topic_service_server.h:73
swri::TopicServiceServerImpl::initialize
void initialize(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const MReq &, MRes &), T *obj)
Definition: topic_service_server.h:55
swri::ImplRoot::~ImplRoot
virtual ~ImplRoot()
Definition: topic_service_server.h:39
swri
Definition: dynamic_parameters.h:51
swri::TopicServiceServerImpl::obj_
T * obj_
Definition: topic_service_server.h:52
swri::TopicServiceServerImpl::callback_
bool(T::* callback_)(const MReq &, MRes &)
Definition: topic_service_server.h:51
ros::NodeHandle
ros::Subscriber


swri_roscpp
Author(s): P. J. Reed
autogenerated on Thu Jun 6 2024 02:33:09