naoqi_driver.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 
00019 #ifndef NAOQI_DRIVER_HPP
00020 #define NAOQI_DRIVER_HPP
00021 
00022 #include <vector>
00023 #include <queue>
00024 
00025 /*
00026 * BOOST
00027 */
00028 #include <boost/property_tree/ptree.hpp>
00029 #include <boost/thread/thread.hpp>
00030 #include <boost/thread/mutex.hpp>
00031 #include <boost/scoped_ptr.hpp>
00032 
00033 /*
00034 * ALDEB
00035 */
00036 #include <qi/session.hpp>
00037 
00038 /*
00039 * PUBLIC INTERFACE
00040 */
00041 #include <naoqi_driver/converter/converter.hpp>
00042 #include <naoqi_driver/publisher/publisher.hpp>
00043 #include <naoqi_driver/subscriber/subscriber.hpp>
00044 #include <naoqi_driver/service/service.hpp>
00045 #include <naoqi_driver/recorder/recorder.hpp>
00046 #include <naoqi_driver/event/event.hpp>
00047 #include <naoqi_driver/recorder/globalrecorder.hpp>
00048 
00049 namespace tf2_ros
00050 {
00051   class Buffer;
00052 }
00053 
00054 namespace naoqi
00055 {
00056 
00057 namespace recorder
00058 {
00059   class GlobalRecorder;
00060 }
00065 class Driver
00066 {
00067 public:
00072   Driver( qi::SessionPtr session, const std::string& prefix );
00073 
00078   ~Driver();
00079 
00080   void init();
00081 
00082   void startRosLoop();
00083   void stopRosLoop();
00087   std::string minidump(const std::string& prefix);
00088   std::string minidumpConverters(const std::string& prefix, const std::vector<std::string>& names);
00089 
00090   void setBufferDuration(float duration);
00091   float getBufferDuration();
00092 
00097   void registerConverter( converter::Converter& conv );
00098 
00104   void registerPublisher( const std::string& conv_name, publisher::Publisher& pub);
00105 
00111   void registerRecorder(const std::string& conv_name, recorder::Recorder& rec, float frequency);
00112 
00116   void registerConverter(converter::Converter conv, publisher::Publisher pub, recorder::Recorder rec );
00117 
00121   void registerPublisher(converter::Converter conv, publisher::Publisher pub );
00122 
00126   void registerRecorder(converter::Converter conv, recorder::Recorder rec );
00127 
00131   bool registerMemoryConverter(const std::string& key, float frequency, const dataType::DataType& type );
00132 
00136   bool registerEventConverter(const std::string& key, const dataType::DataType& type);
00137 
00138 
00142   std::vector<std::string> getAvailableConverters();
00143 
00147   std::vector<std::string> getSubscribedPublishers() const;
00148 
00149   std::string _whoIsYourDaddy()
00150   {
00151     return "A sugar bear";
00152   }
00153 
00161   void registerSubscriber( subscriber::Subscriber sub );
00162 
00170   void registerService( service::Service srv );
00175   std::string getMasterURI() const;
00176 
00182   void setMasterURINet( const std::string& uri, const std::string& network_interface );
00183 
00188   void setMasterURI( const std::string& uri );
00189 
00193   void startPublishing();
00194 
00198   void stopPublishing();
00199 
00203   void startRecording();
00204 
00208   void startRecordingConverters(const std::vector<std::string>& names);
00209 
00213   std::string stopRecording();
00214 
00215   void startLogging();
00216 
00217   void stopLogging();
00218 
00222   void addMemoryConverters(std::string filepath);
00223 
00224   void parseJsonFile(std::string filepath, boost::property_tree::ptree& pt);
00225 
00226   void stopService();
00227 
00228   std::vector<std::string> getFilesList();
00229 
00230   void removeAllFiles();
00231 
00232   void removeFiles(std::vector<std::string> files);
00233 
00234 private:
00235   qi::SessionPtr sessionPtr_;
00236 
00237   const robot::Robot& robot_;
00238 
00239   bool publish_enabled_;
00240   bool record_enabled_;
00241   bool log_enabled_;
00242   bool keep_looping;
00243 
00244   const size_t freq_;
00245   boost::thread publisherThread_;
00246   //ros::Rate r_;
00247 
00248   boost::shared_ptr<recorder::GlobalRecorder> recorder_;
00249 
00250   /* boot config */
00251   boost::property_tree::ptree boot_config_;
00252   void loadBootConfig();
00253 
00254   void registerDefaultConverter();
00255   void registerDefaultSubscriber();
00256   void registerDefaultServices();
00257   void insertEventConverter(const std::string& key, event::Event event);
00258 
00259   template <typename T1, typename T2, typename T3>
00260   void _registerMemoryConverter( const std::string& key, float frequency ) {
00261     boost::shared_ptr<T1> mfp = boost::make_shared<T1>( key );
00262     boost::shared_ptr<T2> mfr = boost::make_shared<T2>( key );
00263     boost::shared_ptr<T3> mfc = boost::make_shared<T3>( key , frequency, sessionPtr_, key );
00264     mfc->registerCallback( message_actions::PUBLISH, boost::bind(&T1::publish, mfp, _1) );
00265     mfc->registerCallback( message_actions::RECORD, boost::bind(&T2::write, mfr, _1) );
00266     mfc->registerCallback( message_actions::LOG, boost::bind(&T2::bufferize, mfr, _1) );
00267     registerConverter( mfc, mfp, mfr );
00268   }
00269 
00270   void rosLoop();
00271 
00272   boost::scoped_ptr<ros::NodeHandle> nhPtr_;
00273   boost::mutex mutex_reinit_;
00274   boost::mutex mutex_conv_queue_;
00275   boost::mutex mutex_record_;
00276 
00277   std::vector< converter::Converter > converters_;
00278   std::map< std::string, publisher::Publisher > pub_map_;
00279   std::map< std::string, recorder::Recorder > rec_map_;
00280   std::map< std::string, event::Event > event_map_;
00281   typedef std::map< std::string, publisher::Publisher>::const_iterator PubConstIter;
00282   typedef std::map< std::string, publisher::Publisher>::iterator PubIter;
00283   typedef std::map< std::string, recorder::Recorder>::const_iterator RecConstIter;
00284   typedef std::map< std::string, recorder::Recorder>::iterator RecIter;
00285   typedef std::map< std::string, event::Event>::const_iterator EventConstIter;
00286   typedef std::map< std::string, event::Event>::iterator EventIter;
00287 
00288   std::vector< subscriber::Subscriber > subscribers_;
00289   std::vector< service::Service > services_;
00290 
00291   float buffer_duration_;
00292 
00294   struct ScheduledConverter {
00295     ScheduledConverter(const ros::Time& schedule, size_t conv_index) :
00296        schedule_(schedule), conv_index_(conv_index)
00297     {
00298     }
00299 
00300     bool operator < (const ScheduledConverter& sp_in) const {
00301       return schedule_ > sp_in.schedule_;
00302     }
00304     ros::Time schedule_;
00306     size_t conv_index_;
00307   };
00308 
00310   std::priority_queue<ScheduledConverter> conv_queue_;
00311 
00315   boost::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
00316 };
00317 
00318 } // naoqi
00319 
00320 #endif


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