recorder.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 RECORDER_HPP
19 #define RECORDER_HPP
20 
21 #include <string>
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 # include <boost/thread/mutex.hpp>
26 
27 #include <ros/ros.h>
28 #include <rosbag/bag.h>
29 #include <rosbag/view.h>
30 #include <geometry_msgs/TransformStamped.h>
31 
33 
34 namespace naoqi
35 {
36 namespace recorder
37 {
38 
46 class Recorder
47 {
48 
49 public:
50 
54  template<typename T>
55  Recorder( T rec ):
56  recPtr_( boost::make_shared<RecorderModel<T> >(rec) )
57  {}
58 
63  bool isInitialized() const
64  {
65  return recPtr_->isInitialized();
66  }
67 
68 
69  void subscribe( bool state )
70  {
71  recPtr_->subscribe(state);
72  }
73 
78  bool isSubscribed() const
79  {
80  return recPtr_->isSubscribed();
81  }
82 
83  std::string topic() const
84  {
85  return recPtr_->topic();
86  }
87 
94  {
95  recPtr_->reset( gr, frequency );
96  }
97 
98  void writeDump(const ros::Time& time)
99  {
100  recPtr_->writeDump(time);
101  }
102 
103  void setBufferDuration(float duration)
104  {
105  recPtr_->setBufferDuration(duration);
106  }
107 
108  friend bool operator==( const Recorder& lhs, const Recorder& rhs )
109  {
110  // decision made for OR-comparison since we want to be more restrictive
111  if ( lhs.topic() == rhs.topic() )
112  return true;
113  return false;
114  }
115 
116 private:
117 
122  {
123  virtual ~RecorderConcept(){}
124  virtual bool isInitialized() const = 0;
125  virtual void subscribe(bool state) = 0;
126  virtual bool isSubscribed() const = 0;
127  virtual std::string topic() const = 0;
128  virtual void writeDump(const ros::Time& time) = 0;
129  virtual void setBufferDuration(float duration) = 0;
130  virtual void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float frequency ) = 0;
131  };
132 
133 
137  template<typename T>
139  {
140  RecorderModel( const T& other ):
141  recorder_( other )
142  {}
143 
145  {
146  recorder_->reset( gr, frequency );
147  }
148 
149  bool isInitialized() const
150  {
151  return recorder_->isInitialized();
152  }
153 
154  void subscribe(bool state)
155  {
156  recorder_->subscribe( state );
157  }
158 
159  bool isSubscribed() const
160  {
161  return recorder_->isSubscribed();
162  }
163 
164  std::string topic() const
165  {
166  return recorder_->topic();
167  }
168 
169  void writeDump(const ros::Time& time)
170  {
171  recorder_->writeDump(time);
172  }
173 
174  void setBufferDuration(float duration)
175  {
176  recorder_->setBufferDuration(duration);
177  }
178 
180  };
181 
183 
184 }; // class recorder
185 
186 } // recorder
187 } //naoqi
188 
189 #endif
virtual void subscribe(bool state)=0
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
initializes/resets the recorder into ROS with a given nodehandle, this will be called at first for in...
Definition: recorder.hpp:93
void setBufferDuration(float duration)
Definition: recorder.hpp:174
boost::shared_ptr< RecorderConcept > recPtr_
Definition: recorder.hpp:182
Recorder concept interface.
Definition: recorder.hpp:46
void setBufferDuration(float duration)
Definition: recorder.hpp:103
virtual std::string topic() const =0
void writeDump(const ros::Time &time)
Definition: recorder.hpp:169
virtual void setBufferDuration(float duration)=0
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
Definition: recorder.hpp:144
friend bool operator==(const Recorder &lhs, const Recorder &rhs)
Definition: recorder.hpp:108
bool isSubscribed() const
checks if the recorder has a subscription and is hence allowed to record
Definition: recorder.hpp:78
std::string topic() const
Definition: recorder.hpp:83
virtual void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)=0
void writeDump(const ros::Time &time)
Definition: recorder.hpp:98
Recorder(T rec)
Constructor for recorder interface.
Definition: recorder.hpp:55
virtual void writeDump(const ros::Time &time)=0
bool isInitialized() const
checks if the recorder is correctly initialized on the ros-master @
Definition: recorder.hpp:63
void subscribe(bool state)
Definition: recorder.hpp:69


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