recorder/basic.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 BASIC_RECORDER_HPP
19 #define BASIC_RECORDER_HPP
20 
21 /*
22 * LOCAL includes
23 */
25 #include "../helpers/recorder_helpers.hpp"
26 
27 /*
28 * STANDARD includes
29 */
30 #include <string>
31 #include <boost/circular_buffer.hpp>
32 
33 namespace naoqi
34 {
35 namespace recorder
36 {
37 
38 template<class T>
40 {
41 
42 public:
43  BasicRecorder( const std::string& topic, float buffer_frequency = 0 ):
44  topic_( topic ),
45  buffer_duration_( helpers::recorder::bufferDefaultDuration ),
46  is_initialized_( false ),
47  is_subscribed_( false ),
48  buffer_frequency_(buffer_frequency),
49  counter_(1)
50  {}
51 
52  virtual ~BasicRecorder() {}
53 
54  inline std::string topic() const
55  {
56  return topic_;
57  }
58 
59  inline bool isInitialized() const
60  {
61  return is_initialized_;
62  }
63 
64  inline void subscribe( bool state)
65  {
66  is_subscribed_ = state;
67  }
68 
69  inline bool isSubscribed() const
70  {
71  return is_subscribed_;
72  }
73 
74  virtual void write(const T& msg)
75  {
76  if (!msg.header.stamp.isZero()) {
77  gr_->write(topic_, msg, msg.header.stamp);
78  }
79  else {
80  gr_->write(topic_, msg);
81  }
82  }
83 
84  virtual void writeDump(const ros::Time& time)
85  {
86  boost::mutex::scoped_lock lock_write_buffer( mutex_ );
87  typename boost::circular_buffer<T>::iterator it;
88  for (it = buffer_.begin(); it != buffer_.end(); it++)
89  {
90  if (!it->header.stamp.isZero()) {
91  gr_->write(topic_, *it, it->header.stamp);
92  }
93  else {
94  gr_->write(topic_, *it);
95  }
96  }
97  }
98 
99  virtual void bufferize(const T& msg)
100  {
101  boost::mutex::scoped_lock lock_bufferize( mutex_ );
102  if (counter_ < max_counter_)
103  {
104  counter_++;
105  }
106  else
107  {
108  counter_ = 1;
109  buffer_.push_back(msg);
110  }
111  }
112 
113  virtual void reset(boost::shared_ptr<GlobalRecorder> gr, float conv_frequency)
114  {
115  gr_ = gr;
116  conv_frequency_ = conv_frequency;
117  if (buffer_frequency_ != 0)
118  {
119  max_counter_ = static_cast<int>(conv_frequency/buffer_frequency_);
120  buffer_size_ = static_cast<size_t>(buffer_duration_*(conv_frequency/max_counter_));
121  }
122  else
123  {
124  max_counter_ = 1;
125  buffer_size_ = static_cast<size_t>(buffer_duration_*conv_frequency);
126  }
127  buffer_.resize(buffer_size_);
128  is_initialized_ = true;
129  }
130 
131  virtual void setBufferDuration(float duration)
132  {
133  boost::mutex::scoped_lock lock_bufferize( mutex_ );
134  buffer_size_ = static_cast<size_t>(duration*(conv_frequency_/max_counter_));
135  buffer_duration_ = duration;
136  buffer_.set_capacity(buffer_size_);
137  }
138 
139 protected:
140  std::string topic_;
141 
142  boost::circular_buffer<T> buffer_;
143  size_t buffer_size_;
145  boost::mutex mutex_;
146 
149 
151 
154  int counter_;
156 
157 }; // class
158 
159 } // publisher
160 } // naoqi
161 
162 #endif
boost::circular_buffer< T > buffer_
virtual void bufferize(const T &msg)
virtual void writeDump(const ros::Time &time)
virtual void write(const T &msg)
virtual void setBufferDuration(float duration)
BasicRecorder(const std::string &topic, float buffer_frequency=0)
static const float bufferDefaultDuration
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
virtual void reset(boost::shared_ptr< GlobalRecorder > gr, float conv_frequency)


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