log.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 LOG_RECORDER_HPP
00019 #define LOG_RECORDER_HPP
00020 
00021 /*
00022 * BOOST includes
00023 */
00024 #include <boost/circular_buffer.hpp>
00025 
00026 /*
00027 * LOCAL includes
00028 */
00029 #include <naoqi_driver/recorder/globalrecorder.hpp>
00030 #include "../helpers/recorder_helpers.hpp"
00031 
00032 /*
00033 * ROS includes
00034 */
00035 #include <ros/ros.h>
00036 #include <rosgraph_msgs/Log.h>
00037 
00038 namespace naoqi
00039 {
00040 namespace recorder
00041 {
00042 
00043 class LogRecorder
00044 {
00045 
00046 public:
00047   LogRecorder( const std::string& topic, float buffer_frequency = 0 );
00048 
00049   void write( std::list<rosgraph_msgs::Log>& log_msgs );
00050 
00051   void reset(boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float conv_frequency );
00052 
00053   void bufferize( std::list<rosgraph_msgs::Log>& log_msgs );
00054 
00055   void writeDump(const ros::Time& time);
00056 
00057   void setBufferDuration(float duration);
00058 
00059   inline std::string topic() const
00060   {
00061     return topic_;
00062   }
00063 
00064   inline bool isInitialized() const
00065   {
00066     return is_initialized_;
00067   }
00068 
00069   inline void subscribe( bool state)
00070   {
00071     is_subscribed_ = state;
00072   }
00073 
00074   inline bool isSubscribed() const
00075   {
00076     return is_subscribed_;
00077   }
00078 
00079 protected:
00080   std::string topic_;
00081 
00082   boost::circular_buffer< std::list<rosgraph_msgs::Log> > buffer_;
00083   size_t buffer_size_;
00084   float buffer_duration_;
00085 
00086   boost::mutex mutex_;
00087 
00088   bool is_initialized_;
00089   bool is_subscribed_;
00090 
00091   boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr_;
00092 
00093   float buffer_frequency_;
00094   float conv_frequency_;
00095   int counter_;
00096   int max_counter_;
00097 
00098 }; // class
00099 
00100 } //publisher
00101 } // naoqi
00102 
00103 #endif


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