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 SUBSCRIBER_HPP 00019 #define SUBSCRIBER_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 subscriber 00031 { 00032 00033 00041 class Subscriber 00042 { 00043 00044 public: 00045 00049 template<typename T> 00050 Subscriber( T sub ): 00051 subPtr_( boost::make_shared<SubscriberModel<T> >(sub) ) 00052 {} 00053 00058 bool isInitialized() const 00059 { 00060 return subPtr_->isInitialized(); 00061 } 00062 00068 void reset( ros::NodeHandle& nh ) 00069 { 00070 std::cout << name() << " is resetting" << std::endl; 00071 subPtr_->reset( nh ); 00072 std::cout << name() << " reset" << std::endl; 00073 } 00074 00079 std::string name() const 00080 { 00081 return subPtr_->name(); 00082 } 00083 00088 std::string topic() const 00089 { 00090 return subPtr_->topic(); 00091 } 00092 00093 friend bool operator==( const Subscriber& lhs, const Subscriber& rhs ) 00094 { 00095 // decision made for OR-comparison since we want to be more restrictive 00096 if ( lhs.name() == rhs.name() || lhs.topic() == rhs.topic() ) 00097 return true; 00098 return false; 00099 } 00100 00101 private: 00102 00106 struct SubscriberConcept 00107 { 00108 virtual ~SubscriberConcept(){} 00109 virtual bool isInitialized() const = 0; 00110 virtual void reset( ros::NodeHandle& nh ) = 0; 00111 virtual std::string name() const = 0; 00112 virtual std::string topic() const = 0; 00113 }; 00114 00115 00119 template<typename T> 00120 struct SubscriberModel : public SubscriberConcept 00121 { 00122 SubscriberModel( const T& other ): 00123 subscriber_( other ) 00124 {} 00125 00126 std::string name() const 00127 { 00128 return subscriber_->name(); 00129 } 00130 00131 std::string topic() const 00132 { 00133 return subscriber_->topic(); 00134 } 00135 00136 bool isInitialized() const 00137 { 00138 return subscriber_->isInitialized(); 00139 } 00140 00141 void reset( ros::NodeHandle& nh ) 00142 { 00143 subscriber_->reset( nh ); 00144 } 00145 00146 T subscriber_; 00147 }; 00148 00149 boost::shared_ptr<SubscriberConcept> subPtr_; 00150 00151 }; // class subscriber 00152 00153 } //subscriber 00154 } //naoqi 00155 00156 #endif