service.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #ifndef SERVICE_HPP
00019 #define SERVICE_HPP
00020 
00021 #include <string>
00022 
00023 #include <boost/make_shared.hpp>
00024 #include <boost/shared_ptr.hpp>
00025 
00026 #include <ros/ros.h>
00027 
00028 namespace naoqi
00029 {
00030 namespace service
00031 {
00032 
00033 
00041 class Service
00042 {
00043 
00044 public:
00045 
00049   template<typename T>
00050   Service( T srv ):
00051     srvPtr_( boost::make_shared<ServiceModel<T> >(srv) )
00052   {}
00053 
00059   void reset( ros::NodeHandle& nh )
00060   {
00061     std::cout << name() << " is resetting" << std::endl;
00062     srvPtr_->reset( nh );
00063     std::cout << name() << " reset" << std::endl;
00064   }
00065 
00070   std::string name() const
00071   {
00072     return srvPtr_->name();
00073   }
00074 
00079   std::string topic() const
00080   {
00081     return srvPtr_->topic();
00082   }
00083 
00084 private:
00085 
00089   struct ServiceConcept
00090   {
00091     virtual ~ServiceConcept(){}
00092     virtual void reset( ros::NodeHandle& nh ) = 0;
00093     virtual std::string name() const = 0;
00094     virtual std::string topic() const = 0;
00095   };
00096 
00097 
00101   template<typename T>
00102   struct ServiceModel : public ServiceConcept
00103   {
00104     ServiceModel( const T& other ):
00105       service_( other )
00106     {}
00107 
00108     std::string name() const
00109     {
00110       return service_->name();
00111     }
00112 
00113     std::string topic() const
00114     {
00115       return service_->topic();
00116     }
00117 
00118     bool isInitialized() const
00119     {
00120       return service_->isInitialized();
00121     }
00122 
00123     void reset( ros::NodeHandle& nh )
00124     {
00125       service_->reset( nh );
00126     }
00127 
00128     T service_;
00129   };
00130 
00131   boost::shared_ptr<ServiceConcept> srvPtr_;
00132 
00133 }; // class service
00134 
00135 } //service
00136 } //naoqi
00137 
00138 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56