event/basic.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef EVENT_REGISTER_HPP
19 #define EVENT_REGISTER_HPP
20 
21 #include <string>
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 #include <boost/thread/mutex.hpp>
26 
27 #include <qi/session.hpp>
28 
29 #include <ros/ros.h>
30 
31 #include <naoqi_driver/tools.hpp>
33 
34 namespace naoqi
35 {
36 
44 template <typename Converter, typename Publisher, typename Recorder>
46 {
47 
48 public:
49 
53  EventRegister();
54  EventRegister( const std::string& key, const qi::SessionPtr& session );
56 
57  void resetPublisher( ros::NodeHandle& nh );
59 
60  void startProcess();
61  void stopProcess();
62 
63  void writeDump(const ros::Time& time);
64  void setBufferDuration(float duration);
65 
66  void isRecording(bool state);
67  void isPublishing(bool state);
68  void isDumping(bool state);
69 
70 private:
71  void registerCallback();
72  void unregisterCallback();
73  void onEvent();
74 
75 private:
79 
80  qi::AnyObject p_memory_;
81  qi::AnyObject signal_;
82  qi::SignalLink signalID_;
83  std::string key_;
84 
85  boost::mutex mutex_;
86 
87  bool isStarted_;
90  bool isDumping_;
91 
92 }; // class globalrecorder
93 } //naoqi
94 #include "basic.hxx"
95 
96 #endif
void writeDump(const ros::Time &time)
qi::AnyObject signal_
Definition: event/basic.hpp:81
boost::shared_ptr< Publisher > publisher_
Definition: event/basic.hpp:77
qi::AnyObject p_memory_
Definition: event/basic.hpp:80
boost::mutex mutex_
Definition: event/basic.hpp:85
void isRecording(bool state)
void resetPublisher(ros::NodeHandle &nh)
void setBufferDuration(float duration)
boost::shared_ptr< Converter > converter_
Definition: event/basic.hpp:76
EventRegister()
Constructor for recorder interface.
boost::shared_ptr< Recorder > recorder_
Definition: event/basic.hpp:78
void isPublishing(bool state)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
qi::SignalLink signalID_
Definition: event/basic.hpp:82
GlobalRecorder concept interface.
Definition: event/basic.hpp:45
void isDumping(bool state)


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26