naoqidriver
naoqi_driver.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 
19 #ifndef NAOQI_DRIVER_HPP
20 #define NAOQI_DRIVER_HPP
21 
22 #include <vector>
23 #include <queue>
24 
25 /*
26 * BOOST
27 */
28 #include <boost/property_tree/ptree.hpp>
29 #include <boost/thread/thread.hpp>
30 #include <boost/thread/mutex.hpp>
31 #include <boost/scoped_ptr.hpp>
32 
33 /*
34 * ALDEB
35 */
36 #include <qi/session.hpp>
37 
38 /*
39 * PUBLIC INTERFACE
40 */
48 
49 namespace tf2_ros
50 {
51  class Buffer;
52 }
53 
54 namespace naoqi
55 {
56 
57 namespace recorder
58 {
59  class GlobalRecorder;
60 }
65 class Driver
66 {
67 public:
72  Driver( qi::SessionPtr& session, const std::string& prefix );
73 
78  ~Driver();
79 
80  void init();
81 
82  void startRosLoop();
83  void stopRosLoop();
87  std::string minidump(const std::string& prefix);
88  std::string minidumpConverters(const std::string& prefix, const std::vector<std::string>& names);
89 
90  void setBufferDuration(float duration);
91  float getBufferDuration();
92 
98 
104  void registerPublisher( const std::string& conv_name, publisher::Publisher& pub);
105 
111  void registerRecorder(const std::string& conv_name, recorder::Recorder& rec, float frequency);
112 
117 
122 
127 
131  bool registerMemoryConverter(const std::string& key, float frequency, const dataType::DataType& type );
132 
136  bool registerEventConverter(const std::string& key, const dataType::DataType& type);
137 
138 
142  std::vector<std::string> getAvailableConverters();
143 
147  std::vector<std::string> getSubscribedPublishers() const;
148 
149  std::string _whoIsYourDaddy()
150  {
151  return "the coolest German in Paris";
152  }
153 
162 
170  void registerService( service::Service srv );
175  std::string getMasterURI() const;
176 
182  void setMasterURINet( const std::string& uri, const std::string& network_interface );
183 
188  void setMasterURI( const std::string& uri );
189 
193  void startPublishing();
194 
198  void stopPublishing();
199 
203  void startRecording();
204 
208  void startRecordingConverters(const std::vector<std::string>& names);
209 
213  std::string stopRecording();
214 
215  void startLogging();
216 
217  void stopLogging();
218 
222  void addMemoryConverters(std::string filepath);
223 
224  void parseJsonFile(std::string filepath, boost::property_tree::ptree& pt);
225 
226  void stopService();
227 
228  std::vector<std::string> getFilesList();
229 
230  void removeAllFiles();
231 
232  void removeFiles(std::vector<std::string> files);
233 
234 private:
235  qi::SessionPtr sessionPtr_;
236 
238 
243 
244  const size_t freq_;
245  boost::thread publisherThread_;
246  //ros::Rate r_;
247 
248  boost::shared_ptr<recorder::GlobalRecorder> recorder_;
249 
250  /* boot config */
251  boost::property_tree::ptree boot_config_;
252  void loadBootConfig();
253 
257  void insertEventConverter(const std::string& key, event::Event event);
258 
259  template <typename T1, typename T2, typename T3>
260  void _registerMemoryConverter( const std::string& key, float frequency ) {
261  boost::shared_ptr<T1> mfp = boost::make_shared<T1>( key );
262  boost::shared_ptr<T2> mfr = boost::make_shared<T2>( key );
263  boost::shared_ptr<T3> mfc = boost::make_shared<T3>( key , frequency, sessionPtr_, key );
264  mfc->registerCallback( message_actions::PUBLISH, boost::bind(&T1::publish, mfp, _1) );
265  mfc->registerCallback( message_actions::RECORD, boost::bind(&T2::write, mfr, _1) );
266  mfc->registerCallback( message_actions::LOG, boost::bind(&T2::bufferize, mfr, _1) );
267  registerConverter( mfc, mfp, mfr );
268  }
269 
270  void rosLoop();
271 
272  boost::scoped_ptr<ros::NodeHandle> nhPtr_;
273  boost::mutex mutex_reinit_;
274  boost::mutex mutex_conv_queue_;
275  boost::mutex mutex_record_;
276 
277  std::vector< converter::Converter > converters_;
278  std::map< std::string, publisher::Publisher > pub_map_;
279  std::map< std::string, recorder::Recorder > rec_map_;
280  std::map< std::string, event::Event > event_map_;
281  typedef std::map< std::string, publisher::Publisher>::const_iterator PubConstIter;
282  typedef std::map< std::string, publisher::Publisher>::iterator PubIter;
283  typedef std::map< std::string, recorder::Recorder>::const_iterator RecConstIter;
284  typedef std::map< std::string, recorder::Recorder>::iterator RecIter;
285  typedef std::map< std::string, event::Event>::const_iterator EventConstIter;
286  typedef std::map< std::string, event::Event>::iterator EventIter;
287 
288  std::vector< subscriber::Subscriber > subscribers_;
289  std::vector< service::Service > services_;
290 
292 
295  ScheduledConverter(const ros::Time& schedule, size_t conv_index) :
296  schedule_(schedule), conv_index_(conv_index)
297  {
298  }
299 
300  bool operator < (const ScheduledConverter& sp_in) const {
301  return schedule_ > sp_in.schedule_;
302  }
304  ros::Time schedule_;
306  size_t conv_index_;
307  };
308 
310  std::priority_queue<ScheduledConverter> conv_queue_;
311 
315  boost::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
316 };
317 
318 } // naoqi
319 
320 #endif
Converter concept interface.
Definition: converter.hpp:42
void rosLoop()
Definition: naoqi_driver.cpp:165
std::map< std::string, recorder::Recorder >::iterator RecIter
Definition: naoqi_driver.hpp:284
void startPublishing()
qicli call function to start/enable publishing all registered publisher
Definition: naoqi_driver.cpp:900
void removeFiles(std::vector< std::string > files)
Definition: naoqi_driver.cpp:1257
bool registerEventConverter(const std::string &key, const dataType::DataType &type)
qicli call function to register a converter for a given memory event
Definition: naoqi_driver.cpp:1143
void stopRosLoop()
Definition: naoqi_driver.cpp:1054
void stopLogging()
Definition: naoqi_driver.cpp:1037
Driver(qi::SessionPtr &session, const std::string &prefix)
Constructor for naoqi driver.
Definition: naoqi_driver.cpp:112
qi::SessionPtr sessionPtr_
Definition: naoqi_driver.hpp:235
std::vector< converter::Converter > converters_
Definition: naoqi_driver.hpp:277
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher
Definition: naoqi_driver.cpp:417
Definition: message_actions.h:13
void stopService()
Definition: naoqi_driver.cpp:157
void startLogging()
Definition: naoqi_driver.cpp:1032
Recorder concept interface.
Definition: recorder.hpp:46
static std::string prefix
Definition: ros_env.hpp:64
Definition: naoqi_driver.hpp:294
void registerSubscriber(subscriber::Subscriber sub)
registers a subscriber
Definition: naoqi_driver.cpp:763
std::string getMasterURI() const
qicli call function to get current master uri
Definition: naoqi_driver.cpp:822
std::vector< std::string > getSubscribedPublishers() const
get all subscribed publishers
Definition: naoqi_driver.cpp:918
void startRosLoop()
Definition: naoqi_driver.cpp:1042
Definition: audio.cpp:29
Subscriber concept interface.
Definition: subscriber.hpp:41
Definition: message_actions.h:12
bool log_enabled_
Definition: naoqi_driver.hpp:241
void parseJsonFile(std::string filepath, boost::property_tree::ptree &pt)
Definition: naoqi_driver.cpp:1065
boost::mutex mutex_conv_queue_
Definition: naoqi_driver.hpp:274
ros::Time schedule_
Definition: naoqi_driver.hpp:304
bool registerMemoryConverter(const std::string &key, float frequency, const dataType::DataType &type)
qicli call function to register a converter for a given memory key
Definition: naoqi_driver.cpp:461
std::map< std::string, publisher::Publisher >::iterator PubIter
Definition: naoqi_driver.hpp:282
Robot
Definition: tools.hpp:37
void loadBootConfig()
Definition: naoqi_driver.cpp:147
DataType
Definition: tools.hpp:52
void registerDefaultConverter()
Definition: naoqi_driver.cpp:523
boost::property_tree::ptree boot_config_
Definition: naoqi_driver.hpp:251
const size_t freq_
Definition: naoqi_driver.hpp:244
Definition: message_actions.h:11
std::vector< subscriber::Subscriber > subscribers_
Definition: naoqi_driver.hpp:288
boost::scoped_ptr< ros::NodeHandle > nhPtr_
Definition: naoqi_driver.hpp:272
boost::thread publisherThread_
Definition: naoqi_driver.hpp:245
Converter concept interface.
Definition: event.hpp:44
bool operator<(const ScheduledConverter &sp_in) const
Definition: naoqi_driver.hpp:300
std::string stopRecording()
qicli call function to stop recording all registered publisher in a ROSbag
Definition: naoqi_driver.cpp:1013
bool keep_looping
Definition: naoqi_driver.hpp:242
void stopPublishing()
qicli call function to stop/disable publishing all registered publisher
Definition: naoqi_driver.cpp:909
Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is se...
Definition: naoqi_driver.hpp:65
Publisher concept interface.
Definition: publisher.hpp:41
std::map< std::string, event::Event > event_map_
Definition: naoqi_driver.hpp:280
void registerDefaultServices()
Definition: naoqi_driver.cpp:798
std::map< std::string, publisher::Publisher >::const_iterator PubConstIter
Definition: naoqi_driver.hpp:281
size_t conv_index_
Definition: naoqi_driver.hpp:306
void startRecording()
qicli call function to start recording all registered converter in a ROSbag
Definition: naoqi_driver.cpp:934
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
Definition: naoqi_driver.hpp:315
boost::shared_ptr< recorder::GlobalRecorder > recorder_
Definition: naoqi_driver.hpp:248
void removeAllFiles()
Definition: naoqi_driver.cpp:1244
bool publish_enabled_
Definition: naoqi_driver.hpp:239
boost::mutex mutex_record_
Definition: naoqi_driver.hpp:275
std::string minidump(const std::string &prefix)
Write a ROSbag with the last bufferized data (10s by default)
Definition: naoqi_driver.cpp:246
std::vector< std::string > getFilesList()
Definition: naoqi_driver.cpp:1229
void setMasterURI(const std::string &uri)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:827
const robot::Robot & robot_
Definition: naoqi_driver.hpp:237
std::priority_queue< ScheduledConverter > conv_queue_
Definition: naoqi_driver.hpp:310
std::string minidumpConverters(const std::string &prefix, const std::vector< std::string > &names)
Definition: naoqi_driver.cpp:305
void _registerMemoryConverter(const std::string &key, float frequency)
Definition: naoqi_driver.hpp:260
Definition: naoqi_driver.hpp:49
~Driver()
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.
Definition: naoqi_driver.cpp:126
void addMemoryConverters(std::string filepath)
qicli call function to add on-the-fly some memory keys extractors
Definition: naoqi_driver.cpp:1074
void setMasterURINet(const std::string &uri, const std::string &network_interface)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:832
void init()
Definition: naoqi_driver.cpp:137
std::vector< service::Service > services_
Definition: naoqi_driver.hpp:289
void registerDefaultSubscriber()
Definition: naoqi_driver.cpp:784
std::vector< std::string > getAvailableConverters()
get all available converters
Definition: naoqi_driver.cpp:803
bool record_enabled_
Definition: naoqi_driver.hpp:240
ScheduledConverter(const ros::Time &schedule, size_t conv_index)
Definition: naoqi_driver.hpp:295
std::string _whoIsYourDaddy()
Definition: naoqi_driver.hpp:149
void insertEventConverter(const std::string &key, event::Event event)
Definition: naoqi_driver.cpp:435
void registerRecorder(const std::string &conv_name, recorder::Recorder &rec, float frequency)
prepare and register a recorder
Definition: naoqi_driver.cpp:427
std::map< std::string, event::Event >::const_iterator EventConstIter
Definition: naoqi_driver.hpp:285
std::map< std::string, recorder::Recorder >::const_iterator RecConstIter
Definition: naoqi_driver.hpp:283
void setBufferDuration(float duration)
Definition: naoqi_driver.cpp:390
boost::mutex mutex_reinit_
Definition: naoqi_driver.hpp:273
void registerService(service::Service srv)
registers a service
Definition: naoqi_driver.cpp:792
std::map< std::string, recorder::Recorder > rec_map_
Definition: naoqi_driver.hpp:279
void startRecordingConverters(const std::vector< std::string > &names)
qicli call function to start recording given topics in a ROSbag
Definition: naoqi_driver.cpp:959
std::map< std::string, event::Event >::iterator EventIter
Definition: naoqi_driver.hpp:286
float getBufferDuration()
Definition: naoqi_driver.cpp:403
float buffer_duration_
Definition: naoqi_driver.hpp:291
Service concept interface.
Definition: service.hpp:41
std::map< std::string, publisher::Publisher > pub_map_
Definition: naoqi_driver.hpp:278
void registerConverter(converter::Converter &conv)
registers generall converter units they are connected via callbacks to various actions such as record...
Definition: naoqi_driver.cpp:408