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  std::cout << name() << " reset" << std::endl;
64  }
65 
70  std::string name() const
71  {
72  return srvPtr_->name();
73  }
74 
79  std::string topic() const
80  {
81  return srvPtr_->topic();
82  }
83 
84 private:
85 
90  {
91  virtual ~ServiceConcept(){}
92  virtual void reset( ros::NodeHandle& nh ) = 0;
93  virtual std::string name() const = 0;
94  virtual std::string topic() const = 0;
95  };
96 
97 
101  template<typename T>
102  struct ServiceModel : public ServiceConcept
103  {
104  ServiceModel( const T& other ):
105  service_( other )
106  {}
107 
108  std::string name() const
109  {
110  return service_->name();
111  }
112 
113  std::string topic() const
114  {
115  return service_->topic();
116  }
117 
118  bool isInitialized() const
119  {
120  return service_->isInitialized();
121  }
122 
123  void reset( ros::NodeHandle& nh )
124  {
125  service_->reset( nh );
126  }
127 
129  };
130 
132 
133 }; // class service
134 
135 } //service
136 } //naoqi
137 
138 #endif
naoqi::service::Service::ServiceModel
Definition: service.hpp:102
boost::shared_ptr
ros.h
naoqi::service::Service::ServiceModel::reset
void reset(ros::NodeHandle &nh)
Definition: service.hpp:123
naoqi::service::Service
Service concept interface.
Definition: service.hpp:41
boost
naoqi::service::Service::name
std::string name() const
getting the descriptive name for this service instance
Definition: service.hpp:70
naoqi::service::Service::ServiceModel::service_
T service_
Definition: service.hpp:128
naoqi::service::Service::ServiceConcept::~ServiceConcept
virtual ~ServiceConcept()
Definition: service.hpp:91
naoqi
Definition: converter.hpp:29
naoqi::service::Service::ServiceConcept
Definition: service.hpp:89
naoqi::service::Service::ServiceModel::ServiceModel
ServiceModel(const T &other)
Definition: service.hpp:104
naoqi::service::Service::reset
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
naoqi::service::Service::srvPtr_
boost::shared_ptr< ServiceConcept > srvPtr_
Definition: service.hpp:131
naoqi::service::Service::Service
Service(T srv)
Constructor for service interface.
Definition: service.hpp:50
naoqi::service::Service::ServiceConcept::reset
virtual void reset(ros::NodeHandle &nh)=0
naoqi::service::Service::ServiceModel::topic
std::string topic() const
Definition: service.hpp:113
naoqi::service::Service::ServiceModel::isInitialized
bool isInitialized() const
Definition: service.hpp:118
naoqi::service::Service::ServiceConcept::name
virtual std::string name() const =0
naoqi::service::Service::topic
std::string topic() const
getting the topic to service on
Definition: service.hpp:79
naoqi::service::Service::ServiceModel::name
std::string name() const
Definition: service.hpp:108
naoqi::service::Service::ServiceConcept::topic
virtual std::string topic() const =0
ros::NodeHandle


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06