naoqidriver
service.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef SERVICE_HPP
19 #define SERVICE_HPP
20 
21 #include <string>
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 
26 #include <ros/ros.h>
27 
28 namespace naoqi
29 {
30 namespace service
31 {
32 
33 
41 class Service
42 {
43 
44 public:
45 
49  template<typename T>
50  Service( T srv ):
51  srvPtr_( boost::make_shared<ServiceModel<T> >(srv) )
52  {}
53 
59  void reset( ros::NodeHandle& nh )
60  {
61  std::cout << name() << " is resetting" << std::endl;
62  srvPtr_->reset( nh );
63  }
64 
69  std::string name() const
70  {
71  return srvPtr_->name();
72  }
73 
78  std::string topic() const
79  {
80  return srvPtr_->topic();
81  }
82 
83 private:
84 
89  {
90  virtual ~ServiceConcept(){}
91  virtual void reset( ros::NodeHandle& nh ) = 0;
92  virtual std::string name() const = 0;
93  virtual std::string topic() const = 0;
94  };
95 
96 
100  template<typename T>
101  struct ServiceModel : public ServiceConcept
102  {
103  ServiceModel( const T& other ):
104  service_( other )
105  {}
106 
107  std::string name() const
108  {
109  return service_->name();
110  }
111 
112  std::string topic() const
113  {
114  return service_->topic();
115  }
116 
117  bool isInitialized() const
118  {
119  return service_->isInitialized();
120  }
121 
122  void reset( ros::NodeHandle& nh )
123  {
124  service_->reset( nh );
125  }
126 
128  };
129 
130  boost::shared_ptr<ServiceConcept> srvPtr_;
131 
132 }; // class service
133 
134 } //service
135 } //naoqi
136 
137 #endif
void reset(ros::NodeHandle &nh)
initializes/resets the service into ROS with a given nodehandle, this will be called at first for ini...
Definition: service.hpp:59
void reset(ros::NodeHandle &nh)
Definition: service.hpp:122
std::string topic() const
Definition: service.hpp:112
std::string name() const
getting the descriptive name for this service instance
Definition: service.hpp:69
std::string topic() const
getting the topic to service on
Definition: service.hpp:78
boost::shared_ptr< ServiceConcept > srvPtr_
Definition: service.hpp:130
Definition: audio.cpp:29
T service_
Definition: service.hpp:127
std::string name() const
Definition: service.hpp:107
virtual ~ServiceConcept()
Definition: service.hpp:90
Definition: service.hpp:88
virtual void reset(ros::NodeHandle &nh)=0
bool isInitialized() const
Definition: service.hpp:117
ServiceModel(const T &other)
Definition: service.hpp:103
virtual std::string name() const =0
Definition: service.hpp:101
Service(T srv)
Constructor for service interface.
Definition: service.hpp:50
Service concept interface.
Definition: service.hpp:41
virtual std::string topic() const =0