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   }
00064 
00069   std::string name() const
00070   {
00071     return srvPtr_->name();
00072   }
00073 
00078   std::string topic() const
00079   {
00080     return srvPtr_->topic();
00081   }
00082 
00083 private:
00084 
00088   struct ServiceConcept
00089   {
00090     virtual ~ServiceConcept(){}
00091     virtual void reset( ros::NodeHandle& nh ) = 0;
00092     virtual std::string name() const = 0;
00093     virtual std::string topic() const = 0;
00094   };
00095 
00096 
00100   template<typename T>
00101   struct ServiceModel : public ServiceConcept
00102   {
00103     ServiceModel( const T& other ):
00104       service_( other )
00105     {}
00106 
00107     std::string name() const
00108     {
00109       return service_->name();
00110     }
00111 
00112     std::string topic() const
00113     {
00114       return service_->topic();
00115     }
00116 
00117     bool isInitialized() const
00118     {
00119       return service_->isInitialized();
00120     }
00121 
00122     void reset( ros::NodeHandle& nh )
00123     {
00124       service_->reset( nh );
00125     }
00126 
00127     T service_;
00128   };
00129 
00130   boost::shared_ptr<ServiceConcept> srvPtr_;
00131 
00132 }; // class service
00133 
00134 } //service
00135 } //naoqi
00136 
00137 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14