basic.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #ifndef BASIC_RECORDER_HPP
00019 #define BASIC_RECORDER_HPP
00020 
00021 /*
00022 * LOCAL includes
00023 */
00024 #include <naoqi_driver/recorder/globalrecorder.hpp>
00025 #include "../helpers/recorder_helpers.hpp"
00026 
00027 /*
00028 * STANDARD includes
00029 */
00030 #include <string>
00031 #include <boost/circular_buffer.hpp>
00032 
00033 namespace naoqi
00034 {
00035 namespace recorder
00036 {
00037 
00038 template<class T>
00039 class BasicRecorder
00040 {
00041 
00042 public:
00043   BasicRecorder( const std::string& topic, float buffer_frequency = 0 ):
00044     topic_( topic ),
00045     buffer_duration_( helpers::recorder::bufferDefaultDuration ),
00046     is_initialized_( false ),
00047     is_subscribed_( false ),
00048     buffer_frequency_(buffer_frequency),
00049     counter_(1)
00050   {}
00051 
00052   virtual ~BasicRecorder() {}
00053 
00054   inline std::string topic() const
00055   {
00056     return topic_;
00057   }
00058 
00059   inline bool isInitialized() const
00060   {
00061     return is_initialized_;
00062   }
00063 
00064   inline void subscribe( bool state)
00065   {
00066     is_subscribed_ = state;
00067   }
00068 
00069   inline bool isSubscribed() const
00070   {
00071     return is_subscribed_;
00072   }
00073 
00074   virtual void write(const T& msg)
00075   {
00076     if (!msg.header.stamp.isZero()) {
00077       gr_->write(topic_, msg, msg.header.stamp);
00078     }
00079     else {
00080       gr_->write(topic_, msg);
00081     }
00082   }
00083 
00084   virtual void writeDump(const ros::Time& time)
00085   {
00086     boost::mutex::scoped_lock lock_write_buffer( mutex_ );
00087     typename boost::circular_buffer<T>::iterator it;
00088     for (it = buffer_.begin(); it != buffer_.end(); it++)
00089     {
00090       if (!it->header.stamp.isZero()) {
00091         gr_->write(topic_, *it, it->header.stamp);
00092       }
00093       else {
00094         gr_->write(topic_, *it);
00095       }
00096     }
00097   }
00098 
00099   virtual void bufferize(const T& msg)
00100   {
00101     boost::mutex::scoped_lock lock_bufferize( mutex_ );
00102     if (counter_ < max_counter_)
00103     {
00104       counter_++;
00105     }
00106     else
00107     {
00108       counter_ = 1;
00109       buffer_.push_back(msg);
00110     }
00111   }
00112 
00113   virtual void reset(boost::shared_ptr<GlobalRecorder> gr, float conv_frequency)
00114   {
00115     gr_ = gr;
00116     conv_frequency_ = conv_frequency;
00117     if (buffer_frequency_ != 0)
00118     {
00119       max_counter_ = static_cast<int>(conv_frequency/buffer_frequency_);
00120       buffer_size_ = static_cast<size_t>(buffer_duration_*(conv_frequency/max_counter_));
00121     }
00122     else
00123     {
00124       max_counter_ = 1;
00125       buffer_size_ = static_cast<size_t>(buffer_duration_*conv_frequency);
00126     }
00127     buffer_.resize(buffer_size_);
00128     is_initialized_ = true;
00129   }
00130 
00131   virtual void setBufferDuration(float duration)
00132   {
00133     boost::mutex::scoped_lock lock_bufferize( mutex_ );
00134     buffer_size_ = static_cast<size_t>(duration*(conv_frequency_/max_counter_));
00135     buffer_duration_ = duration;
00136     buffer_.set_capacity(buffer_size_);
00137   }
00138 
00139 protected:
00140   std::string topic_;
00141 
00142   boost::circular_buffer<T> buffer_;
00143   size_t buffer_size_;
00144   float buffer_duration_;
00145   boost::mutex mutex_;
00146 
00147   bool is_initialized_;
00148   bool is_subscribed_;
00149 
00150   boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr_;
00151 
00152   float buffer_frequency_;
00153   float conv_frequency_;
00154   int counter_;
00155   int max_counter_;
00156 
00157 }; // class
00158 
00159 } // publisher
00160 } // naoqi
00161 
00162 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56