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 EVENT_REGISTER_HPP
00019 #define EVENT_REGISTER_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 <qi/session.hpp>
00028 
00029 #include <ros/ros.h>
00030 
00031 #include <naoqi_driver/tools.hpp>
00032 #include <naoqi_driver/recorder/globalrecorder.hpp>
00033 
00034 namespace naoqi
00035 {
00036 
00044 template <typename Converter, typename Publisher, typename Recorder>
00045 class EventRegister
00046 {
00047 
00048 public:
00049 
00053   EventRegister();
00054   EventRegister( const std::string& key, const qi::SessionPtr& session );
00055   ~EventRegister();
00056 
00057   void resetPublisher( ros::NodeHandle& nh );
00058   void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr );
00059 
00060   void startProcess();
00061   void stopProcess();
00062 
00063   void writeDump(const ros::Time& time);
00064   void setBufferDuration(float duration);
00065 
00066   void isRecording(bool state);
00067   void isPublishing(bool state);
00068   void isDumping(bool state);
00069 
00070 private:
00071   void registerCallback();
00072   void unregisterCallback();
00073   void onEvent();
00074 
00075 private:
00076   boost::shared_ptr<Converter> converter_;
00077   boost::shared_ptr<Publisher> publisher_;
00078   boost::shared_ptr<Recorder> recorder_;
00079 
00080   qi::AnyObject p_memory_;
00081   qi::AnyObject signal_;
00082   qi::SignalLink signalID_;
00083   std::string key_;
00084 
00085   boost::mutex mutex_;
00086 
00087   bool isStarted_;
00088   bool isPublishing_;
00089   bool isRecording_;
00090   bool isDumping_;
00091 
00092 }; // class globalrecorder
00093 } //naoqi
00094 #include "basic.hxx"
00095 
00096 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14