naoqidriver
subscriber.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 SUBSCRIBER_HPP
19 #define SUBSCRIBER_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 subscriber
31 {
32 
33 
42 {
43 
44 public:
45 
49  template<typename T>
50  Subscriber( T sub ):
51  subPtr_( boost::make_shared<SubscriberModel<T> >(sub) )
52  {}
53 
58  bool isInitialized() const
59  {
60  return subPtr_->isInitialized();
61  }
62 
68  void reset( ros::NodeHandle& nh )
69  {
70  std::cout << name() << " is resetting" << std::endl;
71  subPtr_->reset( nh );
72  std::cout << name() << " reset" << std::endl;
73  }
74 
79  std::string name() const
80  {
81  return subPtr_->name();
82  }
83 
88  std::string topic() const
89  {
90  return subPtr_->topic();
91  }
92 
93  friend bool operator==( const Subscriber& lhs, const Subscriber& rhs )
94  {
95  // decision made for OR-comparison since we want to be more restrictive
96  if ( lhs.name() == rhs.name() || lhs.topic() == rhs.topic() )
97  return true;
98  return false;
99  }
100 
101 private:
102 
107  {
108  virtual ~SubscriberConcept(){}
109  virtual bool isInitialized() const = 0;
110  virtual void reset( ros::NodeHandle& nh ) = 0;
111  virtual std::string name() const = 0;
112  virtual std::string topic() const = 0;
113  };
114 
115 
119  template<typename T>
121  {
122  SubscriberModel( const T& other ):
123  subscriber_( other )
124  {}
125 
126  std::string name() const
127  {
128  return subscriber_->name();
129  }
130 
131  std::string topic() const
132  {
133  return subscriber_->topic();
134  }
135 
136  bool isInitialized() const
137  {
138  return subscriber_->isInitialized();
139  }
140 
141  void reset( ros::NodeHandle& nh )
142  {
143  subscriber_->reset( nh );
144  }
145 
147  };
148 
149  boost::shared_ptr<SubscriberConcept> subPtr_;
150 
151 }; // class subscriber
152 
153 } //subscriber
154 } //naoqi
155 
156 #endif
Subscriber(T sub)
Constructor for subscriber interface.
Definition: subscriber.hpp:50
bool isInitialized() const
checks if the subscriber is correctly initialized on the ros-master @
Definition: subscriber.hpp:58
T subscriber_
Definition: subscriber.hpp:146
std::string name() const
Definition: subscriber.hpp:126
std::string topic() const
Definition: subscriber.hpp:131
virtual ~SubscriberConcept()
Definition: subscriber.hpp:108
std::string name() const
getting the descriptive name for this subscriber instance
Definition: subscriber.hpp:79
Definition: audio.cpp:29
Subscriber concept interface.
Definition: subscriber.hpp:41
void reset(ros::NodeHandle &nh)
Definition: subscriber.hpp:141
bool isInitialized() const
Definition: subscriber.hpp:136
std::string topic() const
getting the topic to subscriber on
Definition: subscriber.hpp:88
friend bool operator==(const Subscriber &lhs, const Subscriber &rhs)
Definition: subscriber.hpp:93
boost::shared_ptr< SubscriberConcept > subPtr_
Definition: subscriber.hpp:149
SubscriberModel(const T &other)
Definition: subscriber.hpp:122
virtual void reset(ros::NodeHandle &nh)=0
void reset(ros::NodeHandle &nh)
initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for ...
Definition: subscriber.hpp:68