event.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_HPP
00019 #define EVENT_HPP
00020 
00021 #include <string>
00022 
00023 #include <boost/make_shared.hpp>
00024 #include <boost/shared_ptr.hpp>
00025 
00026 #include <ros/ros.h>
00027 #include <naoqi_driver/message_actions.h>
00028 #include <naoqi_driver/recorder/globalrecorder.hpp>
00029 #include <naoqi_driver/tools.hpp>
00030 
00031 namespace naoqi
00032 {
00033 namespace event
00034 {
00035 
00036 
00044 class Event
00045 {
00046 
00047 public:
00048 
00052   template<typename T>
00053   Event( T event ):
00054     eventPtr_( boost::make_shared<EventModel<T> >(event) )
00055   {}
00056 
00057   void resetPublisher( ros::NodeHandle& nh )
00058   {
00059     eventPtr_->resetPublisher(nh);
00060   }
00061 
00062   void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr )
00063   {
00064     eventPtr_->resetRecorder(gr);
00065   }
00066 
00067   void startProcess( )
00068   {
00069     eventPtr_->startProcess();
00070   }
00071 
00072   void stopProcess( )
00073   {
00074     eventPtr_->stopProcess();
00075   }
00076 
00077   void writeDump( const ros::Time& time )
00078   {
00079     eventPtr_->writeDump(time);
00080   }
00081 
00082   void setBufferDuration(float duration)
00083   {
00084     eventPtr_->setBufferDuration(duration);
00085   }
00086 
00087   void isRecording(bool state)
00088   {
00089     eventPtr_->isRecording(state);
00090   }
00091 
00092   void isPublishing(bool state)
00093   {
00094     eventPtr_->isPublishing(state);
00095   }
00096 
00097   void isDumping(bool state)
00098   {
00099     eventPtr_->isDumping(state);
00100   }
00101 
00102 private:
00103 
00107   struct EventConcept
00108   {
00109     virtual ~EventConcept(){}
00110     virtual void resetPublisher(ros::NodeHandle& nh) = 0;
00111     virtual void resetRecorder(boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr) = 0;
00112     virtual void startProcess() = 0;
00113     virtual void stopProcess() = 0;
00114     virtual void writeDump(const ros::Time& time) = 0;
00115     virtual void setBufferDuration(float duration) = 0;
00116     virtual void isRecording(bool state) = 0;
00117     virtual void isPublishing(bool state) = 0;
00118     virtual void isDumping(bool state) = 0;
00119   };
00120 
00121 
00125   template<typename T>
00126   struct EventModel : public EventConcept
00127   {
00128     EventModel( const T& other ):
00129       converter_( other )
00130     {}
00131 
00132     void resetPublisher( ros::NodeHandle& nh )
00133     {
00134       converter_->resetPublisher(nh);
00135     }
00136 
00137     void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr )
00138     {
00139       converter_->resetRecorder(gr);
00140     }
00141 
00142     void startProcess( )
00143     {
00144       converter_->startProcess();
00145     }
00146 
00147     void stopProcess( )
00148     {
00149       converter_->stopProcess();
00150     }
00151 
00152     void writeDump( const ros::Time& time )
00153     {
00154       converter_->writeDump(time);
00155     }
00156 
00157     void setBufferDuration(float duration)
00158     {
00159       converter_->setBufferDuration(duration);
00160     }
00161 
00162     void isRecording(bool state)
00163     {
00164       converter_->isRecording(state);
00165     }
00166 
00167     void isPublishing(bool state)
00168     {
00169       converter_->isPublishing(state);
00170     }
00171 
00172     void isDumping(bool state)
00173     {
00174       converter_->isDumping(state);
00175     }
00176 
00177     T converter_;
00178   };
00179 
00180   boost::shared_ptr<EventConcept> eventPtr_;
00181 
00182 }; // class converter
00183 
00184 } //converter
00185 } //naoqi
00186 
00187 #endif


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