publisher.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 PUBLISHER_HPP
00019 #define PUBLISHER_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 publisher
00031 {
00032 
00033 
00041 class Publisher
00042 {
00043 
00044 public:
00045 
00049   template<typename T>
00050   Publisher( const T& pub ):
00051     pubPtr_( boost::make_shared<PublisherModel<T> >(pub) )
00052   {}
00053 
00058   bool isInitialized() const
00059   {
00060     return pubPtr_->isInitialized();
00061   }
00062 
00067   bool isSubscribed() const
00068   {
00069     return pubPtr_->isSubscribed();
00070   }
00071 
00077   void reset( ros::NodeHandle& nh )
00078   {
00079     std::cout << topic() << " is resetting" << std::endl;
00080     pubPtr_->reset( nh );
00081     std::cout << topic() << " reset" << std::endl;
00082   }
00083 
00088   std::string topic() const
00089   {
00090     return pubPtr_->topic();
00091   }
00092 
00093   friend bool operator==( const Publisher& lhs, const Publisher& rhs )
00094   {
00095     // decision made for OR-comparison since we want to be more restrictive
00096     if ( lhs.topic() == rhs.topic() )
00097       return true;
00098     return false;
00099   }
00100 
00101   friend bool operator==( const boost::shared_ptr<Publisher>& lhs, const boost::shared_ptr<Publisher>& rhs )
00102   {
00103     return operator==( *lhs, *rhs );
00104   }
00105 
00106 private:
00107 
00111   struct PublisherConcept
00112   {
00113     virtual ~PublisherConcept(){}
00114     virtual bool isInitialized() const = 0;
00115     virtual bool isSubscribed() const = 0;
00116     virtual void reset( ros::NodeHandle& nh ) = 0;
00117     virtual std::string topic() const = 0;
00118   };
00119 
00120 
00124   template<typename T>
00125   struct PublisherModel : public PublisherConcept
00126   {
00127     PublisherModel( const T& other ):
00128       publisher_( other )
00129     {}
00130 
00131     std::string topic() const
00132     {
00133       return publisher_->topic();
00134     }
00135 
00136     bool isInitialized() const
00137     {
00138       return publisher_->isInitialized();
00139     }
00140 
00141     bool isSubscribed() const
00142     {
00143       return publisher_->isSubscribed();
00144     }
00145 
00146     void reset( ros::NodeHandle& nh )
00147     {
00148       publisher_->reset( nh );
00149     }
00150 
00151     T publisher_;
00152   };
00153 
00154   boost::shared_ptr<PublisherConcept> pubPtr_;
00155 
00156 }; // class publisher
00157 
00158 } //publisher
00159 } //naoqi
00160 
00161 #endif


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