publisher.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 PUBLISHER_HPP
19 #define PUBLISHER_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 publisher
31 {
32 
33 
41 class Publisher
42 {
43 
44 public:
45 
49  template<typename T>
50  Publisher( const T& pub ):
51  pubPtr_( boost::make_shared<PublisherModel<T> >(pub) )
52  {}
53 
58  bool isInitialized() const
59  {
60  return pubPtr_->isInitialized();
61  }
62 
67  bool isSubscribed() const
68  {
69  return pubPtr_->isSubscribed();
70  }
71 
77  void reset( ros::NodeHandle& nh )
78  {
79  std::cout << topic() << " is resetting" << std::endl;
80  pubPtr_->reset( nh );
81  std::cout << topic() << " reset" << std::endl;
82  }
83 
88  std::string topic() const
89  {
90  return pubPtr_->topic();
91  }
92 
93  friend bool operator==( const Publisher& lhs, const Publisher& rhs )
94  {
95  // decision made for OR-comparison since we want to be more restrictive
96  if ( lhs.topic() == rhs.topic() )
97  return true;
98  return false;
99  }
100 
102  {
103  return operator==( *lhs, *rhs );
104  }
105 
106 private:
107 
112  {
113  virtual ~PublisherConcept(){}
114  virtual bool isInitialized() const = 0;
115  virtual bool isSubscribed() const = 0;
116  virtual void reset( ros::NodeHandle& nh ) = 0;
117  virtual std::string topic() const = 0;
118  };
119 
120 
124  template<typename T>
126  {
127  PublisherModel( const T& other ):
128  publisher_( other )
129  {}
130 
131  std::string topic() const
132  {
133  return publisher_->topic();
134  }
135 
136  bool isInitialized() const
137  {
138  return publisher_->isInitialized();
139  }
140 
141  bool isSubscribed() const
142  {
143  return publisher_->isSubscribed();
144  }
145 
146  void reset( ros::NodeHandle& nh )
147  {
148  publisher_->reset( nh );
149  }
150 
152  };
153 
155 
156 }; // class publisher
157 
158 } //publisher
159 } //naoqi
160 
161 #endif
bool isSubscribed() const
checks if the publisher has a subscription and is hence allowed to publish
Definition: publisher.hpp:67
void reset(ros::NodeHandle &nh)
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for i...
Definition: publisher.hpp:77
bool isInitialized() const
checks if the publisher is correctly initialized on the ros-master @
Definition: publisher.hpp:58
virtual void reset(ros::NodeHandle &nh)=0
boost::shared_ptr< PublisherConcept > pubPtr_
Definition: publisher.hpp:154
virtual std::string topic() const =0
Publisher concept interface.
Definition: publisher.hpp:41
Publisher(const T &pub)
Constructor for publisher interface.
Definition: publisher.hpp:50
std::string topic() const
getting the topic to publish on
Definition: publisher.hpp:88
friend bool operator==(const boost::shared_ptr< Publisher > &lhs, const boost::shared_ptr< Publisher > &rhs)
Definition: publisher.hpp:101
friend bool operator==(const Publisher &lhs, const Publisher &rhs)
Definition: publisher.hpp:93


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26