event.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 EVENT_HPP
19 #define EVENT_HPP
20 
21 #include <string>
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 
26 #include <ros/ros.h>
29 #include <naoqi_driver/tools.hpp>
30 
31 namespace naoqi
32 {
33 namespace event
34 {
35 
36 
44 class Event
45 {
46 
47 public:
48 
52  template<typename T>
53  Event( T event ):
54  eventPtr_( boost::make_shared<EventModel<T> >(event) )
55  {}
56 
58  {
59  eventPtr_->resetPublisher(nh);
60  }
61 
63  {
64  eventPtr_->resetRecorder(gr);
65  }
66 
67  void startProcess( )
68  {
69  eventPtr_->startProcess();
70  }
71 
72  void stopProcess( )
73  {
74  eventPtr_->stopProcess();
75  }
76 
77  void writeDump( const ros::Time& time )
78  {
79  eventPtr_->writeDump(time);
80  }
81 
82  void setBufferDuration(float duration)
83  {
84  eventPtr_->setBufferDuration(duration);
85  }
86 
87  void isRecording(bool state)
88  {
89  eventPtr_->isRecording(state);
90  }
91 
92  void isPublishing(bool state)
93  {
94  eventPtr_->isPublishing(state);
95  }
96 
97  void isDumping(bool state)
98  {
99  eventPtr_->isDumping(state);
100  }
101 
102 private:
103 
108  {
109  virtual ~EventConcept(){}
110  virtual void resetPublisher(ros::NodeHandle& nh) = 0;
112  virtual void startProcess() = 0;
113  virtual void stopProcess() = 0;
114  virtual void writeDump(const ros::Time& time) = 0;
115  virtual void setBufferDuration(float duration) = 0;
116  virtual void isRecording(bool state) = 0;
117  virtual void isPublishing(bool state) = 0;
118  virtual void isDumping(bool state) = 0;
119  };
120 
121 
125  template<typename T>
126  struct EventModel : public EventConcept
127  {
128  EventModel( const T& other ):
129  converter_( other )
130  {}
131 
133  {
134  converter_->resetPublisher(nh);
135  }
136 
138  {
139  converter_->resetRecorder(gr);
140  }
141 
142  void startProcess( )
143  {
144  converter_->startProcess();
145  }
146 
147  void stopProcess( )
148  {
149  converter_->stopProcess();
150  }
151 
152  void writeDump( const ros::Time& time )
153  {
154  converter_->writeDump(time);
155  }
156 
157  void setBufferDuration(float duration)
158  {
159  converter_->setBufferDuration(duration);
160  }
161 
162  void isRecording(bool state)
163  {
164  converter_->isRecording(state);
165  }
166 
167  void isPublishing(bool state)
168  {
169  converter_->isPublishing(state);
170  }
171 
172  void isDumping(bool state)
173  {
174  converter_->isDumping(state);
175  }
176 
178  };
179 
181 
182 }; // class converter
183 
184 } //converter
185 } //naoqi
186 
187 #endif
tools.hpp
naoqi::event::Event::EventConcept::stopProcess
virtual void stopProcess()=0
naoqi::event::Event::EventConcept::setBufferDuration
virtual void setBufferDuration(float duration)=0
naoqi::event::Event::EventModel::setBufferDuration
void setBufferDuration(float duration)
Definition: event.hpp:157
naoqi::event::Event::isPublishing
void isPublishing(bool state)
Definition: event.hpp:92
boost::shared_ptr< naoqi::recorder::GlobalRecorder >
naoqi::event::Event::EventConcept::writeDump
virtual void writeDump(const ros::Time &time)=0
naoqi::event::Event::EventConcept::isDumping
virtual void isDumping(bool state)=0
naoqi::event::Event::EventModel::isPublishing
void isPublishing(bool state)
Definition: event.hpp:167
ros.h
naoqi::event::Event::EventModel::isRecording
void isRecording(bool state)
Definition: event.hpp:162
boost
naoqi::event::Event::EventModel::isDumping
void isDumping(bool state)
Definition: event.hpp:172
naoqi::event::Event::EventConcept::startProcess
virtual void startProcess()=0
naoqi::event::Event::EventConcept::resetRecorder
virtual void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)=0
naoqi::event::Event::resetPublisher
void resetPublisher(ros::NodeHandle &nh)
Definition: event.hpp:57
naoqi::event::Event::EventModel
Definition: event.hpp:126
naoqi::event::Event::EventConcept::resetPublisher
virtual void resetPublisher(ros::NodeHandle &nh)=0
naoqi::event::Event::EventModel::startProcess
void startProcess()
Definition: event.hpp:142
naoqi::event::Event::EventConcept::isRecording
virtual void isRecording(bool state)=0
naoqi
Definition: converter.hpp:29
naoqi::event::Event::EventModel::writeDump
void writeDump(const ros::Time &time)
Definition: event.hpp:152
naoqi::event::Event::stopProcess
void stopProcess()
Definition: event.hpp:72
naoqi::event::Event::Event
Event(T event)
Constructor for converter interface.
Definition: event.hpp:53
naoqi::event::Event::writeDump
void writeDump(const ros::Time &time)
Definition: event.hpp:77
naoqi::event::Event::isRecording
void isRecording(bool state)
Definition: event.hpp:87
naoqi::event::Event::resetRecorder
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event.hpp:62
naoqi::event::Event::startProcess
void startProcess()
Definition: event.hpp:67
ros::Time
globalrecorder.hpp
naoqi::event::Event
Converter concept interface.
Definition: event.hpp:44
message_actions.h
naoqi::event::Event::eventPtr_
boost::shared_ptr< EventConcept > eventPtr_
Definition: event.hpp:180
naoqi::event::Event::EventConcept::~EventConcept
virtual ~EventConcept()
Definition: event.hpp:109
naoqi::event::Event::EventConcept
Definition: event.hpp:107
naoqi::event::Event::EventModel::resetPublisher
void resetPublisher(ros::NodeHandle &nh)
Definition: event.hpp:132
naoqi::event::Event::EventModel::stopProcess
void stopProcess()
Definition: event.hpp:147
naoqi::event::Event::EventModel::EventModel
EventModel(const T &other)
Definition: event.hpp:128
naoqi::event::Event::EventModel::resetRecorder
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event.hpp:137
naoqi::event::Event::isDumping
void isDumping(bool state)
Definition: event.hpp:97
naoqi::event::Event::EventModel::converter_
T converter_
Definition: event.hpp:177
naoqi::event::Event::EventConcept::isPublishing
virtual void isPublishing(bool state)=0
naoqi::event::Event::setBufferDuration
void setBufferDuration(float duration)
Definition: event.hpp:82
ros::NodeHandle


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06