recorder.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 RECORDER_HPP
00019 #define RECORDER_HPP
00020 
00021 #include <string>
00022 
00023 #include <boost/make_shared.hpp>
00024 #include <boost/shared_ptr.hpp>
00025 # include <boost/thread/mutex.hpp>
00026 
00027 #include <ros/ros.h>
00028 #include <rosbag/bag.h>
00029 #include <rosbag/view.h>
00030 #include <geometry_msgs/TransformStamped.h>
00031 
00032 #include "naoqi_driver/recorder/globalrecorder.hpp"
00033 
00034 namespace naoqi
00035 {
00036 namespace recorder
00037 {
00038 
00046 class Recorder
00047 {
00048 
00049 public:
00050 
00054   template<typename T>
00055   Recorder( T rec ):
00056     recPtr_( boost::make_shared<RecorderModel<T> >(rec) )
00057   {}
00058 
00063   bool isInitialized() const
00064   {
00065     return recPtr_->isInitialized();
00066   }
00067 
00068 
00069   void subscribe( bool state )
00070   {
00071     recPtr_->subscribe(state);
00072   }
00073 
00078   bool isSubscribed() const
00079   {
00080     return recPtr_->isSubscribed();
00081   }
00082 
00083   std::string topic() const
00084   {
00085     return recPtr_->topic();
00086   }
00087 
00093   void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float frequency)
00094   {
00095     recPtr_->reset( gr, frequency );
00096   }
00097 
00098   void writeDump(const ros::Time& time)
00099   {
00100     recPtr_->writeDump(time);
00101   }
00102 
00103   void setBufferDuration(float duration)
00104   {
00105     recPtr_->setBufferDuration(duration);
00106   }
00107 
00108   friend bool operator==( const Recorder& lhs, const Recorder& rhs )
00109   {
00110     // decision made for OR-comparison since we want to be more restrictive
00111     if ( lhs.topic() == rhs.topic() )
00112       return true;
00113     return false;
00114   }
00115 
00116 private:
00117 
00121   struct RecorderConcept
00122   {
00123     virtual ~RecorderConcept(){}
00124     virtual bool isInitialized() const = 0;
00125     virtual void subscribe(bool state) = 0;
00126     virtual bool isSubscribed() const = 0;
00127     virtual std::string topic() const = 0;
00128     virtual void writeDump(const ros::Time& time) = 0;
00129     virtual void setBufferDuration(float duration) = 0;
00130     virtual void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float frequency ) = 0;
00131   };
00132 
00133 
00137   template<typename T>
00138   struct RecorderModel : public RecorderConcept
00139   {
00140     RecorderModel( const T& other ):
00141       recorder_( other )
00142     {}
00143 
00144     void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float frequency )
00145     {
00146       recorder_->reset( gr, frequency );
00147     }
00148 
00149     bool isInitialized() const
00150     {
00151       return recorder_->isInitialized();
00152     }
00153 
00154     void subscribe(bool state)
00155     {
00156       recorder_->subscribe( state );
00157     }
00158 
00159     bool isSubscribed() const
00160     {
00161       return recorder_->isSubscribed();
00162     }
00163 
00164     std::string topic() const
00165     {
00166       return recorder_->topic();
00167     }
00168 
00169     void writeDump(const ros::Time& time)
00170     {
00171       recorder_->writeDump(time);
00172     }
00173 
00174     void setBufferDuration(float duration)
00175     {
00176       recorder_->setBufferDuration(duration);
00177     }
00178 
00179     T recorder_;
00180   };
00181 
00182   boost::shared_ptr<RecorderConcept> recPtr_;
00183 
00184 }; // class recorder
00185 
00186 } // recorder
00187 } //naoqi
00188 
00189 #endif


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