naoqi_driver.cpp
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  * PUBLIC INTERFACE
00020  */
00021 #include <naoqi_driver/naoqi_driver.hpp>
00022 #include <naoqi_driver/message_actions.h>
00023 
00024 /*
00025  * CONVERTERS
00026  */
00027 #include "converters/audio.hpp"
00028 #include "converters/touch.hpp"
00029 #include "converters/camera.hpp"
00030 #include "converters/diagnostics.hpp"
00031 #include "converters/imu.hpp"
00032 #include "converters/info.hpp"
00033 #include "converters/joint_state.hpp"
00034 #include "converters/laser.hpp"
00035 #include "converters/memory_list.hpp"
00036 #include "converters/sonar.hpp"
00037 #include "converters/memory/bool.hpp"
00038 #include "converters/memory/float.hpp"
00039 #include "converters/memory/int.hpp"
00040 #include "converters/memory/string.hpp"
00041 #include "converters/log.hpp"
00042 #include "converters/odom.hpp"
00043 
00044 /*
00045  * PUBLISHERS
00046  */
00047 #include "publishers/basic.hpp"
00048 #include "publishers/camera.hpp"
00049 #include "publishers/info.hpp"
00050 #include "publishers/joint_state.hpp"
00051 #include "publishers/log.hpp"
00052 #include "publishers/sonar.hpp"
00053 
00054 /*
00055  * TOOLS
00056  */
00057 #include "tools/robot_description.hpp"
00058 #include "tools/alvisiondefinitions.h" // for kTop...
00059 
00060 /*
00061  * SUBSCRIBERS
00062  */
00063 #include "subscribers/teleop.hpp"
00064 #include "subscribers/moveto.hpp"
00065 #include "subscribers/speech.hpp"
00066 
00067 
00068 /*
00069  * SERVICES
00070  */
00071 #include "services/robot_config.hpp"
00072 
00073 /*
00074  * RECORDERS
00075  */
00076 #include "recorder/basic.hpp"
00077 #include "recorder/basic_event.hpp"
00078 #include "recorder/camera.hpp"
00079 #include "recorder/diagnostics.hpp"
00080 #include "recorder/joint_state.hpp"
00081 #include "recorder/sonar.hpp"
00082 
00083 /*
00084  * EVENTS
00085  */
00086 #include "event/basic.hpp"
00087 #include "event/audio.hpp"
00088 #include "event/touch.hpp"
00089 
00090 /*
00091  * STATIC FUNCTIONS INCLUDE
00092  */
00093 #include "ros_env.hpp"
00094 #include "helpers/filesystem_helpers.hpp"
00095 #include "helpers/recorder_helpers.hpp"
00096 #include "helpers/naoqi_helpers.hpp"
00097 #include "helpers/driver_helpers.hpp"
00098 
00099 /*
00100  * ROS
00101  */
00102 #include <tf2_ros/buffer.h>
00103 
00104 /*
00105  * BOOST
00106  */
00107 #include <boost/foreach.hpp>
00108 #include <boost/property_tree/json_parser.hpp>
00109 #define for_each BOOST_FOREACH
00110 
00111 #define DEBUG 0
00112 
00113 namespace naoqi
00114 {
00115 
00116 Driver::Driver( qi::SessionPtr session, const std::string& prefix )
00117   : sessionPtr_( session ),
00118   robot_( helpers::driver::getRobot(session) ),
00119   freq_(15),
00120   publish_enabled_(false),
00121   record_enabled_(false),
00122   log_enabled_(false),
00123   keep_looping(true),
00124   recorder_(boost::make_shared<recorder::GlobalRecorder>(prefix)),
00125   buffer_duration_(helpers::recorder::bufferDefaultDuration)
00126 {
00127   if(prefix == ""){
00128     std::cout << "Error driver prefix must not be empty" << std::endl;
00129     throw new ros::Exception("Error driver prefix must not be empty");
00130   }
00131   else {
00132     naoqi::ros_env::setPrefix(prefix);
00133   }
00134 
00135 }
00136 
00137 Driver::~Driver()
00138 {
00139   std::cout << "naoqi driver is shutting down.." << std::endl;
00140   // destroy nodehandle?
00141   if(nhPtr_)
00142   {
00143     nhPtr_->shutdown();
00144     ros::shutdown();
00145   }
00146 }
00147 
00148 void Driver::init()
00149 {
00150   ros::Time::init(); // can call this many times
00151   loadBootConfig();
00152   registerDefaultConverter();
00153   registerDefaultSubscriber();
00154   registerDefaultServices();
00155   startRosLoop();
00156 }
00157 
00158 void Driver::loadBootConfig()
00159 {
00160   const std::string& file_path = helpers::filesystem::getBootConfigFile();
00161   std::cout << "load boot config from " << file_path << std::endl;
00162   if (!file_path.empty())
00163   {
00164     boost::property_tree::read_json( file_path, boot_config_ );
00165   }
00166 }
00167 
00168 void Driver::stopService() {
00169   stopRosLoop();
00170   converters_.clear();
00171   subscribers_.clear();
00172   event_map_.clear();
00173 }
00174 
00175 
00176 void Driver::rosLoop()
00177 {
00178   static std::vector<message_actions::MessageAction> actions;
00179 
00180 //  ros::Time::init();
00181   while( keep_looping )
00182   {
00183     // clear the callback triggers
00184     actions.clear();
00185     {
00186       boost::mutex::scoped_lock lock( mutex_conv_queue_ );
00187       if (!conv_queue_.empty())
00188       {
00189         // Wait for the next Publisher to be ready
00190         size_t conv_index = conv_queue_.top().conv_index_;
00191         converter::Converter& conv = converters_[conv_index];
00192         ros::Time schedule = conv_queue_.top().schedule_;
00193 
00194         // check the publishing condition
00195         // 1. publishing enabled
00196         // 2. has to be registered
00197         // 3. has to be subscribed
00198         PubConstIter pub_it = pub_map_.find( conv.name() );
00199         if ( publish_enabled_ &&  pub_it != pub_map_.end() && pub_it->second.isSubscribed() )
00200         {
00201           actions.push_back(message_actions::PUBLISH);
00202         }
00203 
00204         // check the recording condition
00205         // 1. recording enabled
00206         // 2. has to be registered
00207         // 3. has to be subscribed (configured to be recorded)
00208         RecConstIter rec_it = rec_map_.find( conv.name() );
00209         {
00210           boost::mutex::scoped_lock lock_record( mutex_record_, boost::try_to_lock );
00211           if ( lock_record && record_enabled_ && rec_it != rec_map_.end() && rec_it->second.isSubscribed() )
00212           {
00213             actions.push_back(message_actions::RECORD);
00214           }
00215         }
00216 
00217         // bufferize data in recorder
00218         if ( log_enabled_ && rec_it != rec_map_.end() && conv.frequency() != 0)
00219         {
00220           actions.push_back(message_actions::LOG);
00221         }
00222 
00223         // only call when we have at least one action to perform
00224         if (actions.size() >0)
00225         {
00226           conv.callAll( actions );
00227         }
00228 
00229         ros::Duration d( schedule - ros::Time::now() );
00230         if ( d > ros::Duration(0))
00231         {
00232           d.sleep();
00233         }
00234 
00235         // Schedule for a future time or not
00236         conv_queue_.pop();
00237         if ( conv.frequency() != 0 )
00238         {
00239           conv_queue_.push(ScheduledConverter(schedule + ros::Duration(1.0f / conv.frequency()), conv_index));
00240         }
00241 
00242       }
00243       else // conv_queue is empty.
00244       {
00245         // sleep one second
00246         ros::Duration(1).sleep();
00247       }
00248     } // mutex scope
00249 
00250     if ( publish_enabled_ )
00251     {
00252       ros::spinOnce();
00253     }
00254   } // while loop
00255 }
00256 
00257 std::string Driver::minidump(const std::string& prefix)
00258 {
00259   if (!log_enabled_)
00260   {
00261     const std::string& err = "Log is not enabled, please enable logging before calling minidump";
00262     std::cout << BOLDRED << err << std::endl
00263               << RESETCOLOR << std::endl;
00264     return err;
00265   }
00266 
00267   // CHECK SIZE IN FOLDER
00268   long files_size = 0;
00269   boost::filesystem::path folderPath(boost::filesystem::current_path());
00270   helpers::filesystem::getFilesSize(folderPath, files_size);
00271   if (files_size > helpers::filesystem::folderMaximumSize)
00272   {
00273     std::cout << BOLDRED << "No more space on robot. You need to upload the presents bags and remove them to make new ones."
00274                  << std::endl << "To remove all the presents bags, you can run this command:" << std::endl
00275                     << "\t$ qicli call ROS-Driver.removeFiles" << RESETCOLOR << std::endl;
00276     return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
00277   }
00278 
00279   // IF A ROSBAG WAS OPENED, FIRST CLOSE IT
00280   if (record_enabled_)
00281   {
00282     stopRecording();
00283   }
00284 
00285   // STOP BUFFERIZING
00286   log_enabled_ = false;
00287   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00288   {
00289     iterator->second.isDumping(true);
00290   }
00291   ros::Time time = ros::Time::now();
00292 
00293   // START A NEW ROSBAG
00294   boost::mutex::scoped_lock lock_record( mutex_record_ );
00295   recorder_->startRecord(prefix);
00296 
00297   // WRITE ALL BUFFER INTO THE ROSBAG
00298   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00299   {
00300     iterator->second.writeDump(time);
00301   }
00302   for(RecIter iterator = rec_map_.begin(); iterator != rec_map_.end(); iterator++)
00303   {
00304     iterator->second.writeDump(time);
00305   }
00306 
00307   // RESTART BUFFERIZING
00308   log_enabled_ = true;
00309   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00310   {
00311     iterator->second.isDumping(false);
00312   }
00313   return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
00314 }
00315 
00316 std::string Driver::minidumpConverters(const std::string& prefix, const std::vector<std::string>& names)
00317 {
00318   if (!log_enabled_)
00319   {
00320     const std::string& err = "Log is not enabled, please enable logging before calling minidump";
00321     std::cout << BOLDRED << err << std::endl
00322               << RESETCOLOR << std::endl;
00323     return err;
00324   }
00325 
00326   // CHECK SIZE IN FOLDER
00327   long files_size = 0;
00328   boost::filesystem::path folderPath(boost::filesystem::current_path());
00329   helpers::filesystem::getFilesSize(folderPath, files_size);
00330   if (files_size > helpers::filesystem::folderMaximumSize)
00331   {
00332     std::cout << BOLDRED << "No more space on robot. You need to upload the presents bags and remove them to make new ones."
00333                  << std::endl << "To remove all the presents bags, you can run this command:" << std::endl
00334                     << "\t$ qicli call ROS-Driver.removeFiles" << RESETCOLOR << std::endl;
00335     return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
00336   }
00337 
00338   // IF A ROSBAG WAS OPENED, FIRST CLOSE IT
00339   if (record_enabled_)
00340   {
00341     stopRecording();
00342   }
00343 
00344   // STOP BUFFERIZING
00345   log_enabled_ = false;
00346   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00347   {
00348     iterator->second.isDumping(true);
00349   }
00350   ros::Time time = ros::Time::now();
00351 
00352   // WRITE CHOOSEN BUFFER INTO THE ROSBAG
00353   boost::mutex::scoped_lock lock_record( mutex_record_ );
00354 
00355   bool is_started = false;
00356   for_each( const std::string& name, names)
00357   {
00358     RecIter it = rec_map_.find(name);
00359     if ( it != rec_map_.end() )
00360     {
00361       if ( !is_started )
00362       {
00363         recorder_->startRecord(prefix);
00364         is_started = true;
00365       }
00366       it->second.writeDump(time);
00367     }
00368     else
00369     {
00370       EventIter it_event = event_map_.find(name);
00371       if ( it_event != event_map_.end() )
00372       {
00373         if ( !is_started )
00374         {
00375           recorder_->startRecord(prefix);
00376           is_started = true;
00377         }
00378         it_event->second.writeDump(time);
00379       }
00380     }
00381   }
00382   // RESTART BUFFERIZING
00383   log_enabled_ = true;
00384   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00385   {
00386     iterator->second.isDumping(false);
00387   }
00388   if ( is_started )
00389   {
00390     return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
00391   }
00392   else
00393   {
00394     std::cout << BOLDRED << "Could not find any topic in recorders" << RESETCOLOR << std::endl
00395       << BOLDYELLOW << "To get the list of all available converter's name, please run:" << RESETCOLOR << std::endl
00396       << GREEN << "\t$ qicli call ROS-Driver.getAvailableConverters" << RESETCOLOR << std::endl;
00397     return "Could not find any topic in converters. To get the list of all available converter's name, please run: $ qicli call ROS-Driver.getAvailableConverters";
00398   }
00399 }
00400 
00401 void Driver::setBufferDuration(float duration)
00402 {
00403   for(RecIter iterator = rec_map_.begin(); iterator != rec_map_.end(); iterator++)
00404   {
00405     iterator->second.setBufferDuration(duration);
00406   }
00407   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00408   {
00409     iterator->second.setBufferDuration(duration);
00410   }
00411   buffer_duration_ = duration;
00412 }
00413 
00414 float Driver::getBufferDuration()
00415 {
00416   return buffer_duration_;
00417 }
00418 
00419 void Driver::registerConverter( converter::Converter& conv )
00420 {
00421   boost::mutex::scoped_lock lock( mutex_conv_queue_ );
00422   int conv_index = converters_.size();
00423   converters_.push_back( conv );
00424   conv.reset();
00425   conv_queue_.push(ScheduledConverter(ros::Time::now(), conv_index));
00426 }
00427 
00428 void Driver::registerPublisher( const std::string& conv_name, publisher::Publisher& pub)
00429 {
00430   if (publish_enabled_) {
00431     pub.reset(*nhPtr_);
00432   }
00433   // Concept classes don't have any default constructors needed by operator[]
00434   // Cannot use this operator here. So we use insert
00435   pub_map_.insert( std::map<std::string, publisher::Publisher>::value_type(conv_name, pub) );
00436 }
00437 
00438 void Driver::registerRecorder( const std::string& conv_name, recorder::Recorder& rec, float frequency)
00439 {
00440   // Concept classes don't have any default constructors needed by operator[]
00441   // Cannot use this operator here. So we use insert
00442   rec.reset(recorder_, frequency);
00443   rec_map_.insert( std::map<std::string, recorder::Recorder>::value_type(conv_name, rec) );
00444 }
00445 
00446 void Driver::insertEventConverter(const std::string& key, event::Event event)
00447 {
00448   //event.reset(*nhPtr_, recorder_);
00449   event.resetRecorder(recorder_);
00450   event_map_.insert( std::map<std::string, event::Event>::value_type(key, event) );
00451 }
00452 
00453 void Driver::registerConverter( converter::Converter conv, publisher::Publisher pub, recorder::Recorder rec )
00454 {
00455   registerConverter( conv );
00456   registerPublisher( conv.name(), pub);
00457   registerRecorder(  conv.name(), rec, conv.frequency());
00458 }
00459 
00460 void Driver::registerPublisher( converter::Converter conv, publisher::Publisher pub )
00461 {
00462   registerConverter( conv );
00463   registerPublisher(conv.name(), pub);
00464 }
00465 
00466 void Driver::registerRecorder( converter::Converter conv, recorder::Recorder rec )
00467 {
00468   registerConverter( conv );
00469   registerRecorder(  conv.name(), rec, conv.frequency());
00470 }
00471 
00472 bool Driver::registerMemoryConverter( const std::string& key, float frequency, const dataType::DataType& type ) {
00473   dataType::DataType data_type;
00474   qi::AnyValue value;
00475   try {
00476     qi::AnyObject p_memory = sessionPtr_->service("ALMemory");
00477     value = p_memory.call<qi::AnyValue>("getData", key);
00478   } catch (const std::exception& e) {
00479     std::cout << BOLDRED << "Could not get data in memory for the key: "
00480               << BOLDCYAN << key << RESETCOLOR << std::endl;
00481     return false;
00482   }
00483 
00484   if (type==dataType::None) {
00485     try {
00486       data_type = helpers::naoqi::getDataType(value);
00487     } catch (const std::exception& e) {
00488       std::cout << BOLDRED << "Could not get a valid data type to register memory converter "
00489                 << BOLDCYAN << key << RESETCOLOR << std::endl
00490                 << BOLDRED << "You can enter it yourself, available types are:" << std::endl
00491                 << "\t > 0 - None" << std::endl
00492                 << "\t > 1 - Float" << std::endl
00493                 << "\t > 2 - Int" << std::endl
00494                 << "\t > 3 - String" << std::endl
00495                 << "\t > 4 - Bool" << RESETCOLOR << std::endl;
00496       return false;
00497     }
00498   }
00499   else {
00500     data_type = type;
00501   }
00502 
00503   switch (data_type) {
00504   case 0:
00505     return false;
00506     break;
00507   case 1:
00508     _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::FloatStamped>,converter::MemoryFloatConverter>(key,frequency);
00509     break;
00510   case 2:
00511     _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::IntStamped>,converter::MemoryIntConverter>(key,frequency);
00512     break;
00513   case 3:
00514     _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped>,converter::MemoryStringConverter>(key,frequency);
00515     break;
00516   case 4:
00517     _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::BoolStamped>,converter::MemoryBoolConverter>(key,frequency);
00518     break;
00519   default:
00520     {
00521       std::cout << BOLDRED << "Wrong data type. Available type are: " << std::endl
00522                    << "\t > 0 - None" << std::endl
00523                    << "\t > 1 - Float" << std::endl
00524                    << "\t > 2 - Int" << std::endl
00525                    << "\t > 3 - String" << std::endl
00526                    << "\t > 4 - Bool" << RESETCOLOR << std::endl;
00527       return false;
00528       break;
00529     }
00530   }
00531   return true;
00532 }
00533 
00534 void Driver::registerDefaultConverter()
00535 {
00536   // init global tf2 buffer
00537   tf2_buffer_.reset<tf2_ros::Buffer>( new tf2_ros::Buffer() );
00538   tf2_buffer_->setUsingDedicatedThread(true);
00539 
00540   // replace this with proper configuration struct
00541   bool info_enabled                   = boot_config_.get( "converters.info.enabled", true);
00542   size_t info_frequency               = boot_config_.get( "converters.info.frequency", 1);
00543 
00544   bool audio_enabled                  = boot_config_.get( "converters.audio.enabled", true);
00545   size_t audio_frequency              = boot_config_.get( "converters.audio.frequency", 1);
00546 
00547   bool logs_enabled                   = boot_config_.get( "converters.logs.enabled", true);
00548   size_t logs_frequency               = boot_config_.get( "converters.logs.frequency", 10);
00549 
00550   bool diag_enabled                   = boot_config_.get( "converters.diag.enabled", true);
00551   size_t diag_frequency               = boot_config_.get( "converters.diag.frequency", 10);
00552 
00553   bool imu_torso_enabled              = boot_config_.get( "converters.imu_torso.enabled", true);
00554   size_t imu_torso_frequency          = boot_config_.get( "converters.imu_torso.frequency", 10);
00555 
00556   bool imu_base_enabled               = boot_config_.get( "converters.imu_base.enabled", true);
00557   size_t imu_base_frequency           = boot_config_.get( "converters.imu_base.frequency", 10);
00558 
00559   bool camera_front_enabled           = boot_config_.get( "converters.front_camera.enabled", true);
00560   size_t camera_front_resolution      = boot_config_.get( "converters.front_camera.resolution", 1); // VGA
00561   size_t camera_front_fps             = boot_config_.get( "converters.front_camera.fps", 10);
00562   size_t camera_front_recorder_fps    = boot_config_.get( "converters.front_camera.recorder_fps", 5);
00563 
00564   bool camera_bottom_enabled          = boot_config_.get( "converters.bottom_camera.enabled", true);
00565   size_t camera_bottom_resolution     = boot_config_.get( "converters.bottom_camera.resolution", 1); // VGA
00566   size_t camera_bottom_fps            = boot_config_.get( "converters.bottom_camera.fps", 10);
00567   size_t camera_bottom_recorder_fps   = boot_config_.get( "converters.bottom_camera.recorder_fps", 5);
00568 
00569   bool camera_depth_enabled           = boot_config_.get( "converters.depth_camera.enabled", true);
00570   size_t camera_depth_resolution      = boot_config_.get( "converters.depth_camera.resolution", 1); // QVGA
00571   size_t camera_depth_fps             = boot_config_.get( "converters.depth_camera.fps", 10);
00572   size_t camera_depth_recorder_fps    = boot_config_.get( "converters.depth_camera.recorder_fps", 5);
00573 
00574   bool camera_ir_enabled              = boot_config_.get( "converters.ir_camera.enabled", true);
00575   size_t camera_ir_resolution         = boot_config_.get( "converters.ir_camera.resolution", 1); // QVGA
00576   size_t camera_ir_fps                = boot_config_.get( "converters.ir_camera.fps", 10);
00577   size_t camera_ir_recorder_fps       = boot_config_.get( "converters.ir_camera.recorder_fps", 5);
00578 
00579   bool joint_states_enabled           = boot_config_.get( "converters.joint_states.enabled", true);
00580   size_t joint_states_frequency       = boot_config_.get( "converters.joint_states.frequency", 50);
00581 
00582   bool laser_enabled                  = boot_config_.get( "converters.laser.enabled", true);
00583   size_t laser_frequency              = boot_config_.get( "converters.laser.frequency", 10);
00584 
00585   bool sonar_enabled                  = boot_config_.get( "converters.sonar.enabled", true);
00586   size_t sonar_frequency              = boot_config_.get( "converters.sonar.frequency", 10);
00587 
00588   bool odom_enabled                  = boot_config_.get( "converters.odom.enabled", true);
00589   size_t odom_frequency              = boot_config_.get( "converters.odom.frequency", 10);
00590 
00591   bool bumper_enabled                 = boot_config_.get( "converters.bumper.enabled", true);
00592   bool hand_enabled                   = boot_config_.get( "converters.touch_hand.enabled", true);
00593   bool head_enabled                   = boot_config_.get( "converters.touch_head.enabled", true);
00594   /*
00595    * The info converter will be called once after it was added to the priority queue. Once it is its turn to be called, its
00596    * callAll method will be triggered (because InfoPublisher is considered to always have subscribers, isSubscribed always
00597    * return true).
00598    * A message is therefore published through InfoPublisher, even if there is nobody to receive it.
00599    * Then, InfoConverter will never be called again, because of its 0Hz frequency. But if a new user subscribes to the "info"
00600    * topic, he/she will receive the information published before, as the publisher is latched.
00601    */
00603   if ( info_enabled )
00604   {
00605     boost::shared_ptr<publisher::InfoPublisher> inp = boost::make_shared<publisher::InfoPublisher>( "info" , robot_);
00606     boost::shared_ptr<recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped> > inr = boost::make_shared<recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped> >( "info" );
00607     boost::shared_ptr<converter::InfoConverter> inc = boost::make_shared<converter::InfoConverter>( "info", 0, sessionPtr_ );
00608     inc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::InfoPublisher::publish, inp, _1) );
00609     inc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped>::write, inr, _1) );
00610     inc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped>::bufferize, inr, _1) );
00611     registerConverter( inc, inp, inr );
00612   }
00613 
00614 
00616   if ( logs_enabled )
00617   {
00618     boost::shared_ptr<converter::LogConverter> lc = boost::make_shared<converter::LogConverter>( "log", logs_frequency, sessionPtr_);
00619     boost::shared_ptr<publisher::LogPublisher> lp = boost::make_shared<publisher::LogPublisher>( "/rosout" );
00620     lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::LogPublisher::publish, lp, _1) );
00621     registerPublisher( lc, lp );
00622   }
00623 
00625   if ( diag_enabled )
00626   {
00627     boost::shared_ptr<converter::DiagnosticsConverter> dc = boost::make_shared<converter::DiagnosticsConverter>( "diag", diag_frequency, sessionPtr_);
00628     boost::shared_ptr<publisher::BasicPublisher<diagnostic_msgs::DiagnosticArray> > dp = boost::make_shared<publisher::BasicPublisher<diagnostic_msgs::DiagnosticArray> >( "/diagnostics" );
00629     boost::shared_ptr<recorder::DiagnosticsRecorder>   dr = boost::make_shared<recorder::DiagnosticsRecorder>( "/diagnostics" );
00630     dc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<diagnostic_msgs::DiagnosticArray>::publish, dp, _1) );
00631     dc->registerCallback( message_actions::RECORD, boost::bind(&recorder::DiagnosticsRecorder::write, dr, _1) );
00632     dc->registerCallback( message_actions::LOG, boost::bind(&recorder::DiagnosticsRecorder::bufferize, dr, _1) );
00633     registerConverter( dc, dp, dr );
00634   }
00635 
00637   if ( imu_torso_enabled )
00638   {
00639     boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::Imu> > imutp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::Imu> >( "imu/torso" );
00640     boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::Imu> > imutr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::Imu> >( "imu/torso" );
00641     boost::shared_ptr<converter::ImuConverter> imutc = boost::make_shared<converter::ImuConverter>( "imu_torso", converter::IMU::TORSO, imu_torso_frequency, sessionPtr_);
00642     imutc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::Imu>::publish, imutp, _1) );
00643     imutc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::write, imutr, _1) );
00644     imutc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::bufferize, imutr, _1) );
00645     registerConverter( imutc, imutp, imutr );
00646   }
00647 
00648   if(robot_ == robot::PEPPER)
00649   {
00651     if ( imu_base_enabled )
00652     {
00653       boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::Imu> > imubp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::Imu> >( "imu/base" );
00654       boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::Imu> > imubr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::Imu> >( "imu/base" );
00655       boost::shared_ptr<converter::ImuConverter> imubc = boost::make_shared<converter::ImuConverter>( "imu_base", converter::IMU::BASE, imu_base_frequency, sessionPtr_);
00656       imubc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::Imu>::publish, imubp, _1) );
00657       imubc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::write, imubr, _1) );
00658       imubc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::bufferize, imubr, _1) );
00659       registerConverter( imubc, imubp, imubr );
00660     }
00661   } // endif PEPPER
00662 
00664   if ( camera_front_enabled )
00665   {
00666     boost::shared_ptr<publisher::CameraPublisher> fcp = boost::make_shared<publisher::CameraPublisher>( "camera/front/image_raw", AL::kTopCamera );
00667     boost::shared_ptr<recorder::CameraRecorder> fcr = boost::make_shared<recorder::CameraRecorder>( "camera/front", camera_front_recorder_fps );
00668     boost::shared_ptr<converter::CameraConverter> fcc = boost::make_shared<converter::CameraConverter>( "front_camera", camera_front_fps, sessionPtr_, AL::kTopCamera, camera_front_resolution );
00669     fcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, fcp, _1, _2) );
00670     fcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, fcr, _1, _2) );
00671     fcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, fcr, _1, _2) );
00672     registerConverter( fcc, fcp, fcr );
00673   }
00674 
00676   if ( camera_bottom_enabled )
00677   {
00678     boost::shared_ptr<publisher::CameraPublisher> bcp = boost::make_shared<publisher::CameraPublisher>( "camera/bottom/image_raw", AL::kBottomCamera );
00679     boost::shared_ptr<recorder::CameraRecorder> bcr = boost::make_shared<recorder::CameraRecorder>( "camera/bottom", camera_bottom_recorder_fps );
00680     boost::shared_ptr<converter::CameraConverter> bcc = boost::make_shared<converter::CameraConverter>( "bottom_camera", camera_bottom_fps, sessionPtr_, AL::kBottomCamera, camera_bottom_resolution );
00681     bcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, bcp, _1, _2) );
00682     bcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, bcr, _1, _2) );
00683     bcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, bcr, _1, _2) );
00684     registerConverter( bcc, bcp, bcr );
00685   }
00686 
00687 
00688   if(robot_ == robot::PEPPER)
00689   {
00691     if ( camera_depth_enabled )
00692     {
00693       boost::shared_ptr<publisher::CameraPublisher> dcp = boost::make_shared<publisher::CameraPublisher>( "camera/depth/image_raw", AL::kDepthCamera );
00694       boost::shared_ptr<recorder::CameraRecorder> dcr = boost::make_shared<recorder::CameraRecorder>( "camera/depth", camera_depth_recorder_fps );
00695       boost::shared_ptr<converter::CameraConverter> dcc = boost::make_shared<converter::CameraConverter>( "depth_camera", camera_depth_fps, sessionPtr_, AL::kDepthCamera, camera_depth_resolution );
00696       dcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, dcp, _1, _2) );
00697       dcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, dcr, _1, _2) );
00698       dcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, dcr, _1, _2) );
00699       registerConverter( dcc, dcp, dcr );
00700     }
00701 
00703     if ( camera_ir_enabled )
00704     {
00705       boost::shared_ptr<publisher::CameraPublisher> icp = boost::make_shared<publisher::CameraPublisher>( "camera/ir/image_raw", AL::kInfraredCamera );
00706       boost::shared_ptr<recorder::CameraRecorder> icr = boost::make_shared<recorder::CameraRecorder>( "camera/ir", camera_ir_recorder_fps );
00707       boost::shared_ptr<converter::CameraConverter> icc = boost::make_shared<converter::CameraConverter>( "infrared_camera", camera_ir_fps, sessionPtr_, AL::kInfraredCamera, camera_ir_resolution);
00708       icc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, icp, _1, _2) );
00709       icc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, icr, _1, _2) );
00710       icc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, icr, _1, _2) );
00711       registerConverter( icc, icp, icr );
00712     }
00713   } // endif PEPPER
00714 
00716   if ( joint_states_enabled )
00717   {
00718     boost::shared_ptr<publisher::JointStatePublisher> jsp = boost::make_shared<publisher::JointStatePublisher>( "/joint_states" );
00719     boost::shared_ptr<recorder::JointStateRecorder> jsr = boost::make_shared<recorder::JointStateRecorder>( "/joint_states" );
00720     boost::shared_ptr<converter::JointStateConverter> jsc = boost::make_shared<converter::JointStateConverter>( "joint_states", joint_states_frequency, tf2_buffer_, sessionPtr_ );
00721     jsc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::JointStatePublisher::publish, jsp, _1, _2) );
00722     jsc->registerCallback( message_actions::RECORD, boost::bind(&recorder::JointStateRecorder::write, jsr, _1, _2) );
00723     jsc->registerCallback( message_actions::LOG, boost::bind(&recorder::JointStateRecorder::bufferize, jsr, _1, _2) );
00724     registerConverter( jsc, jsp, jsr );
00725     //  registerRecorder(jsc, jsr);
00726   }
00727 
00728   if(robot_ == robot::PEPPER)
00729   {
00731     if ( laser_enabled )
00732     {
00733       boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::LaserScan> > lp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::LaserScan> >( "laser" );
00734       boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::LaserScan> > lr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::LaserScan> >( "laser" );
00735       boost::shared_ptr<converter::LaserConverter> lc = boost::make_shared<converter::LaserConverter>( "laser", laser_frequency, sessionPtr_ );
00736       lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::LaserScan>::publish, lp, _1) );
00737       lc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::LaserScan>::write, lr, _1) );
00738       lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::LaserScan>::bufferize, lr, _1) );
00739       registerConverter( lc, lp, lr );
00740     }
00741   }
00742 
00744   if ( sonar_enabled )
00745   {
00746     std::vector<std::string> sonar_topics;
00747     if (robot_ == robot::PEPPER)
00748     {
00749       sonar_topics.push_back("sonar/front");
00750       sonar_topics.push_back("sonar/back");
00751     }
00752     else
00753     {
00754       sonar_topics.push_back("sonar/left");
00755       sonar_topics.push_back("sonar/right");
00756     }
00757     boost::shared_ptr<publisher::SonarPublisher> usp = boost::make_shared<publisher::SonarPublisher>( sonar_topics );
00758     boost::shared_ptr<recorder::SonarRecorder> usr = boost::make_shared<recorder::SonarRecorder>( sonar_topics );
00759     boost::shared_ptr<converter::SonarConverter> usc = boost::make_shared<converter::SonarConverter>( "sonar", sonar_frequency, sessionPtr_ );
00760     usc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::SonarPublisher::publish, usp, _1) );
00761     usc->registerCallback( message_actions::RECORD, boost::bind(&recorder::SonarRecorder::write, usr, _1) );
00762     usc->registerCallback( message_actions::LOG, boost::bind(&recorder::SonarRecorder::bufferize, usr, _1) );
00763     registerConverter( usc, usp, usr );
00764   }
00765 
00766   if ( audio_enabled ) {
00768     boost::shared_ptr<AudioEventRegister> event_register =
00769         boost::make_shared<AudioEventRegister>( "audio", 0, sessionPtr_ );
00770     insertEventConverter("audio", event_register);
00771     if (keep_looping) {
00772       event_map_.find("audio")->second.startProcess();
00773     }
00774     if (publish_enabled_) {
00775       event_map_.find("audio")->second.isPublishing(true);
00776     }
00777   }
00778 
00780   if ( bumper_enabled )
00781   {
00782     std::vector<std::string> bumper_events;
00783     bumper_events.push_back("RightBumperPressed");
00784     bumper_events.push_back("LeftBumperPressed");
00785     if (robot_ == robot::PEPPER)
00786     {
00787       bumper_events.push_back("BackBumperPressed");
00788     }
00789     boost::shared_ptr<BumperEventRegister> event_register =
00790       boost::make_shared<BumperEventRegister>( "bumper", bumper_events, 0, sessionPtr_ );
00791     insertEventConverter("bumper", event_register);
00792     if (keep_looping) {
00793       event_map_.find("bumper")->second.startProcess();
00794     }
00795     if (publish_enabled_) {
00796       event_map_.find("bumper")->second.isPublishing(true);
00797     }
00798   }
00799 
00800   if ( hand_enabled )
00801   {
00802     std::vector<std::string> hand_touch_events;
00803     hand_touch_events.push_back("HandRightBackTouched");
00804     hand_touch_events.push_back("HandRightLeftTouched");
00805     hand_touch_events.push_back("HandRightRightTouched");
00806     hand_touch_events.push_back("HandLeftBackTouched");
00807     hand_touch_events.push_back("HandLeftLeftTouched");
00808     hand_touch_events.push_back("HandLeftRightTouched");
00809     boost::shared_ptr<HandTouchEventRegister> event_register =
00810       boost::make_shared<HandTouchEventRegister>( "hand_touch", hand_touch_events, 0, sessionPtr_ );
00811     insertEventConverter("hand_touch", event_register);
00812     if (keep_looping) {
00813       event_map_.find("hand_touch")->second.startProcess();
00814     }
00815     if (publish_enabled_) {
00816       event_map_.find("hand_touch")->second.isPublishing(true);
00817     }
00818   }
00819 
00820   if ( head_enabled )
00821   {
00822     std::vector<std::string> head_touch_events;
00823     head_touch_events.push_back("FrontTactilTouched");
00824     head_touch_events.push_back("MiddleTactilTouched");
00825     head_touch_events.push_back("RearTactilTouched");
00826     boost::shared_ptr<HeadTouchEventRegister> event_register =
00827       boost::make_shared<HeadTouchEventRegister>( "head_touch", head_touch_events, 0, sessionPtr_ );
00828     insertEventConverter("head_touch", event_register);
00829     if (keep_looping) {
00830       event_map_.find("head_touch")->second.startProcess();
00831     }
00832     if (publish_enabled_) {
00833       event_map_.find("head_touch")->second.isPublishing(true);
00834     }
00835   }
00836 
00838   if ( odom_enabled )
00839   {
00840     boost::shared_ptr<publisher::BasicPublisher<nav_msgs::Odometry> > lp = boost::make_shared<publisher::BasicPublisher<nav_msgs::Odometry> >( "odom" );
00841     boost::shared_ptr<recorder::BasicRecorder<nav_msgs::Odometry> > lr = boost::make_shared<recorder::BasicRecorder<nav_msgs::Odometry> >( "odom" );
00842     boost::shared_ptr<converter::OdomConverter> lc = boost::make_shared<converter::OdomConverter>( "odom", odom_frequency, sessionPtr_ );
00843     lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<nav_msgs::Odometry>::publish, lp, _1) );
00844     lc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::write, lr, _1) );
00845     lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::bufferize, lr, _1) );
00846     registerConverter( lc, lp, lr );
00847   }
00848 
00849 }
00850 
00851 
00852 // public interface here
00853 void Driver::registerSubscriber( subscriber::Subscriber sub )
00854 {
00855   std::vector<subscriber::Subscriber>::iterator it;
00856   it = std::find( subscribers_.begin(), subscribers_.end(), sub );
00857   size_t sub_index = 0;
00858 
00859   // if subscriber is not found, register it!
00860   if (it == subscribers_.end() )
00861   {
00862     sub_index = subscribers_.size();
00863     //sub.reset( *nhPtr_ );
00864     subscribers_.push_back( sub );
00865     std::cout << "registered subscriber:\t" << sub.name() << std::endl;
00866   }
00867   // if found, re-init them
00868   else
00869   {
00870     std::cout << "re-initialized existing subscriber:\t" << it->name() << std::endl;
00871   }
00872 }
00873 
00874 void Driver::registerDefaultSubscriber()
00875 {
00876   if (!subscribers_.empty())
00877     return;
00878   registerSubscriber( boost::make_shared<naoqi::subscriber::TeleopSubscriber>("teleop", "/cmd_vel", "/joint_angles", sessionPtr_) );
00879   registerSubscriber( boost::make_shared<naoqi::subscriber::MovetoSubscriber>("moveto", "/move_base_simple/goal", sessionPtr_, tf2_buffer_) );
00880   registerSubscriber( boost::make_shared<naoqi::subscriber::SpeechSubscriber>("speech", "/speech", sessionPtr_) );
00881 }
00882 
00883 void Driver::registerService( service::Service srv )
00884 {
00885   services_.push_back( srv );
00886 }
00887 
00888 
00889 void Driver::registerDefaultServices()
00890 {
00891   registerService( boost::make_shared<service::RobotConfigService>("robot config service", "/naoqi_driver/get_robot_config", sessionPtr_) );
00892 }
00893 
00894 std::vector<std::string> Driver::getAvailableConverters()
00895 {
00896   std::vector<std::string> conv_list;
00897   for_each( const converter::Converter& conv, converters_ )
00898   {
00899     conv_list.push_back(conv.name());
00900   }
00901   for(EventConstIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00902   {
00903     conv_list.push_back( iterator->first );
00904   }
00905 
00906   return conv_list;
00907 }
00908 
00909 /*
00910 * EXPOSED FUNCTIONS
00911 */
00912 
00913 std::string Driver::getMasterURI() const
00914 {
00915   return ros_env::getMasterURI();
00916 }
00917 
00918 void Driver::setMasterURI( const std::string& uri)
00919 {
00920   setMasterURINet(uri, "eth0");
00921 }
00922 
00923 void Driver::setMasterURINet( const std::string& uri, const std::string& network_interface)
00924 {
00925   // To avoid two calls to this function happening at the same time
00926   boost::mutex::scoped_lock lock( mutex_conv_queue_ );
00927 
00928   // Stopping the loop if there is any
00929   //stopRosLoop();
00930 
00931   // Reinitializing ROS Node
00932   {
00933     nhPtr_.reset();
00934     std::cout << "nodehandle reset " << std::endl;
00935     ros_env::setMasterURI( uri, network_interface );
00936     nhPtr_.reset( new ros::NodeHandle("~") );
00937   }
00938 
00939   if(converters_.empty())
00940   {
00941     // If there is no converters, create them
00942     // (converters only depends on Naoqi, resetting the
00943     // Ros node has no impact on them)
00944     std::cout << BOLDRED << "going to register converters" << RESETCOLOR << std::endl;
00945     registerDefaultConverter();
00946     registerDefaultSubscriber();
00947 //    startRosLoop();
00948   }
00949   else
00950   {
00951     std::cout << "NOT going to re-register the converters" << std::endl;
00952     // If some converters are already there, then
00953     // we just need to reset the registered publisher
00954     // using the new ROS node handler.
00955     typedef std::map< std::string, publisher::Publisher > publisher_map;
00956     for_each( publisher_map::value_type &pub, pub_map_ )
00957     {
00958       pub.second.reset(*nhPtr_);
00959     }
00960 
00961     for_each( subscriber::Subscriber& sub, subscribers_ )
00962     {
00963       std::cout << "resetting subscriber " << sub.name() << std::endl;
00964       sub.reset( *nhPtr_ );
00965     }
00966 
00967     for_each( service::Service& srv, services_ )
00968     {
00969       std::cout << "resetting service " << srv.name() << std::endl;
00970       srv.reset( *nhPtr_ );
00971     }
00972   }
00973 
00974   if (!event_map_.empty()) {
00975     typedef std::map< std::string, event::Event > event_map;
00976     for_each( event_map::value_type &event, event_map_ )
00977     {
00978       event.second.resetPublisher(*nhPtr_);
00979     }
00980   }
00981   // Start publishing again
00982   startPublishing();
00983 
00984   if ( !keep_looping )
00985   {
00986     std::cout << "going to start ROS loop" << std::endl;
00987     startRosLoop();
00988   }
00989 }
00990 
00991 void Driver::startPublishing()
00992 {
00993   publish_enabled_ = true;
00994   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
00995   {
00996     iterator->second.isPublishing(true);
00997   }
00998 }
00999 
01000 void Driver::stopPublishing()
01001 {
01002   publish_enabled_ = false;
01003   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
01004   {
01005     iterator->second.isPublishing(false);
01006   }
01007 }
01008 
01009 std::vector<std::string> Driver::getSubscribedPublishers() const
01010 {
01011   std::vector<std::string> publisher;
01012   for(PubConstIter iterator = pub_map_.begin(); iterator != pub_map_.end(); iterator++)
01013   {
01014     // iterator->first = key
01015     // iterator->second = value
01016     // Repeat if you also want to iterate through the second map.
01017     if ( iterator->second.isSubscribed() )
01018     {
01019       publisher.push_back( iterator->second.topic() );
01020     }
01021   }
01022   return publisher;
01023 }
01024 
01025 void Driver::startRecording()
01026 {
01027   boost::mutex::scoped_lock lock_record( mutex_record_ );
01028   recorder_->startRecord();
01029   for_each( converter::Converter& conv, converters_ )
01030   {
01031     RecIter it = rec_map_.find(conv.name());
01032     if ( it != rec_map_.end() )
01033     {
01034       it->second.subscribe(true);
01035       std::cout << HIGHGREEN << "Topic "
01036                 << BOLDCYAN << conv.name() << RESETCOLOR
01037                 << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
01038     }
01039   }
01040   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
01041   {
01042     iterator->second.isRecording(true);
01043     std::cout << HIGHGREEN << "Topic "
01044               << BOLDCYAN << iterator->first << RESETCOLOR
01045               << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
01046   }
01047   record_enabled_ = true;
01048 }
01049 
01050 void Driver::startRecordingConverters(const std::vector<std::string>& names)
01051 {
01052   boost::mutex::scoped_lock lock_record( mutex_record_ );
01053 
01054   bool is_started = false;
01055   for_each( const std::string& name, names)
01056   {
01057     RecIter it_rec = rec_map_.find(name);
01058     EventIter it_ev = event_map_.find(name);
01059     if ( it_rec != rec_map_.end() )
01060     {
01061       if ( !is_started )
01062       {
01063         recorder_->startRecord();
01064         is_started = true;
01065       }
01066       it_rec->second.subscribe(true);
01067       std::cout << HIGHGREEN << "Topic "
01068         << BOLDCYAN << name << RESETCOLOR
01069         << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
01070     }
01071     else if ( it_ev != event_map_.end() )
01072     {
01073       if ( !is_started )
01074       {
01075         recorder_->startRecord();
01076         is_started = true;
01077       }
01078       it_ev->second.isRecording(true);
01079       std::cout << HIGHGREEN << "Topic "
01080         << BOLDCYAN << name << RESETCOLOR
01081         << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
01082     }
01083     else
01084     {
01085       std::cout << BOLDRED << "Could not find topic "
01086         << BOLDCYAN << name
01087         << BOLDRED << " in recorders" << RESETCOLOR << std::endl
01088         << BOLDYELLOW << "To get the list of all available converter's name, please run:" << RESETCOLOR << std::endl
01089         << GREEN << "\t$ qicli call ROS-Driver.getAvailableConverters" << RESETCOLOR << std::endl;
01090     }
01091   }
01092   if ( is_started )
01093   {
01094     record_enabled_ = true;
01095   }
01096   else
01097   {
01098     std::cout << BOLDRED << "Could not find any topic in recorders" << RESETCOLOR << std::endl
01099       << BOLDYELLOW << "To get the list of all available converter's name, please run:" << RESETCOLOR << std::endl
01100       << GREEN << "\t$ qicli call ROS-Driver.getAvailableConverters" << RESETCOLOR << std::endl;
01101   }
01102 }
01103 
01104 std::string Driver::stopRecording()
01105 {
01106   boost::mutex::scoped_lock lock_record( mutex_record_ );
01107   record_enabled_ = false;
01108   for_each( converter::Converter& conv, converters_ )
01109   {
01110     RecIter it = rec_map_.find(conv.name());
01111     if ( it != rec_map_.end() )
01112     {
01113       it->second.subscribe(false);
01114     }
01115   }
01116   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
01117   {
01118     iterator->second.isRecording(false);
01119   }
01120   return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
01121 }
01122 
01123 void Driver::startLogging()
01124 {
01125   log_enabled_ = true;
01126 }
01127 
01128 void Driver::stopLogging()
01129 {
01130   log_enabled_ = false;
01131 }
01132 
01133 void Driver::startRosLoop()
01134 {
01135   if (publisherThread_.get_id() ==  boost::thread::id())
01136     publisherThread_ = boost::thread( &Driver::rosLoop, this );
01137   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
01138   {
01139     iterator->second.startProcess();
01140   }
01141   // Create the publishing thread if needed
01142   keep_looping = true;
01143 }
01144 
01145 void Driver::stopRosLoop()
01146 {
01147   keep_looping = false;
01148   if (publisherThread_.get_id() !=  boost::thread::id())
01149     publisherThread_.join();
01150   for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
01151   {
01152     iterator->second.stopProcess();
01153   }
01154 }
01155 
01156 void Driver::parseJsonFile(std::string filepath, boost::property_tree::ptree &pt){
01157   // Open json file and parse it
01158   std::ifstream json_file;
01159   json_file.open(filepath.c_str(), std::ios_base::in);
01160 
01161   boost::property_tree::json_parser::read_json(json_file, pt);
01162   json_file.close();
01163 }
01164 
01165 void Driver::addMemoryConverters(std::string filepath){
01166   // Check if the nodeHandle pointer is already initialized
01167   if(!nhPtr_){
01168     std::cout << BOLDRED << "The connection with the ROS master does not seem to be initialized." << std::endl
01169               << BOLDYELLOW << "Please run:" << RESETCOLOR << std::endl
01170               << GREEN << "\t$ qicli call ROS-Driver.setMasterURI <YourROSCoreIP>" << RESETCOLOR << std::endl
01171               << BOLDYELLOW << "before trying to add converters" << RESETCOLOR << std::endl;
01172     return;
01173   }
01174 
01175   // Open the file filepath and parse it
01176   boost::property_tree::ptree pt;
01177   parseJsonFile(filepath, pt);
01178 
01179 
01180   // Get the frequency requested (default to 10 Hz)
01181   float frequency = 10.0f;
01182   try{
01183     frequency = pt.get<float>("frequency");
01184   }
01185   catch(const boost::property_tree::ptree_bad_data& e){
01186     std::cout << "\"frequency\" could not be interpreted as float: " <<  e.what() << std::endl;
01187     std::cout << "Default to 10 Hz" << std::endl;
01188   }
01189   catch(const boost::property_tree::ptree_bad_path& e){
01190     std::cout << "\"frequency\" was not found: " <<  e.what() << std::endl;
01191     std::cout << "Default to 10 Hz" << std::endl;
01192   }
01193 
01194   // Get the topic name requested
01195   std::string topic;
01196   try{
01197     topic = pt.get<std::string>("topic");
01198   }
01199   catch(const boost::property_tree::ptree_error& e){
01200     std::cout << "\"topic\" could not be retrieved: " <<  e.what() << std::endl
01201               << "Cannot add new converters" << std::endl;
01202     return;
01203   }
01204 
01205   std::vector<std::string> list;
01206   try{
01207     BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child("memKeys"))
01208     {
01209       std::string topic = v.second.get_value<std::string>();
01210       list.push_back(topic);
01211     }
01212   }
01213   catch(const boost::property_tree::ptree_error& e){
01214     std::cout << "A problem occured during the reading of the mem keys list: " << e.what() << std::endl
01215               << "Cannot add new converters" << std::endl;
01216     return;
01217   }
01218 
01219   if(list.empty()){
01220     std::cout << "The list of keys to add is empty. " << std::endl;
01221     return;
01222   }
01223 
01224   // Create converter, publisher and recorder
01225   boost::shared_ptr<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> > mlp = boost::make_shared<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> >( topic );
01226   boost::shared_ptr<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> > mlr = boost::make_shared<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> >( topic );
01227   boost::shared_ptr<converter::MemoryListConverter> mlc = boost::make_shared<converter::MemoryListConverter>(list, topic, frequency, sessionPtr_ );
01228   mlc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList>::publish, mlp, _1) );
01229   mlc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::write, mlr, _1) );
01230   mlc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::bufferize, mlr, _1) );
01231   registerConverter( mlc, mlp, mlr );
01232 }
01233 
01234 bool Driver::registerEventConverter(const std::string& key, const dataType::DataType& type)
01235 {
01236   dataType::DataType data_type;
01237   qi::AnyValue value;
01238   try {
01239     qi::AnyObject p_memory = sessionPtr_->service("ALMemory");
01240     value = p_memory.call<qi::AnyValue>("getData", key);
01241   } catch (const std::exception& e) {
01242     std::cout << BOLDRED << "Could not get data in memory for the key: "
01243               << BOLDCYAN << key << RESETCOLOR << std::endl;
01244     return false;
01245   }
01246 
01247   if (type==dataType::None) {
01248     try {
01249       data_type = helpers::naoqi::getDataType(value);
01250     } catch (const std::exception& e) {
01251       std::cout << BOLDRED << "Could not get a valid data type to register memory converter "
01252                 << BOLDCYAN << key << RESETCOLOR << std::endl
01253                 << BOLDRED << "You can enter it yourself, available types are:" << std::endl
01254                 << "\t > 0 - None" << std::endl
01255                 << "\t > 1 - Float" << std::endl
01256                 << "\t > 2 - Int" << std::endl
01257                 << "\t > 3 - String" << std::endl
01258                 << "\t > 4 - Bool" << RESETCOLOR << std::endl;
01259       return false;
01260     }
01261   }
01262   else {
01263     data_type = type;
01264   }
01265 
01266   switch (data_type) {
01267   case 0:
01268     return false;
01269     break;
01270   case 1:
01271     {
01272       boost::shared_ptr<EventRegister<converter::MemoryFloatConverter,publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::FloatStamped> > > event_register =
01273           boost::make_shared<EventRegister<converter::MemoryFloatConverter,publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::FloatStamped> > >( key, sessionPtr_ );
01274       insertEventConverter(key, event_register);
01275       break;
01276     }
01277   case 2:
01278     {
01279       boost::shared_ptr<EventRegister<converter::MemoryIntConverter,publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::IntStamped> > > event_register =
01280           boost::make_shared<EventRegister<converter::MemoryIntConverter,publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::IntStamped> > >( key, sessionPtr_ );
01281       insertEventConverter(key, event_register);
01282       break;
01283     }
01284   case 3:
01285     {
01286       boost::shared_ptr<EventRegister<converter::MemoryStringConverter,publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::StringStamped> > > event_register =
01287           boost::make_shared<EventRegister<converter::MemoryStringConverter,publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::StringStamped> > >( key, sessionPtr_ );
01288       insertEventConverter(key, event_register);
01289       break;
01290     }
01291   case 4:
01292     {
01293       boost::shared_ptr<EventRegister<converter::MemoryBoolConverter,publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::BoolStamped> > > event_register =
01294           boost::make_shared<EventRegister<converter::MemoryBoolConverter,publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::BoolStamped> > >( key, sessionPtr_ );
01295       insertEventConverter(key, event_register);
01296       break;
01297     }
01298   default:
01299     {
01300       std::cout << BOLDRED << "Wrong data type. Available type are: " << std::endl
01301                    << "\t > 0 - None" << std::endl
01302                    << "\t > 1 - Float" << std::endl
01303                    << "\t > 2 - Int" << std::endl
01304                    << "\t > 3 - String" << std::endl
01305                    << "\t > 4 - Bool" << RESETCOLOR << std::endl;
01306       return false;
01307     }
01308   }
01309 
01310   if (keep_looping) {
01311     event_map_.find(key)->second.startProcess();
01312   }
01313   if (publish_enabled_) {
01314     event_map_.find(key)->second.isPublishing(true);
01315   }
01316 
01317   return true;
01318 }
01319 
01320 std::vector<std::string> Driver::getFilesList()
01321 {
01322   std::vector<std::string> fileNames;
01323   boost::filesystem::path folderPath( boost::filesystem::current_path() );
01324   std::vector<boost::filesystem::path> files;
01325   helpers::filesystem::getFiles(folderPath, ".bag", files);
01326 
01327   for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
01328        it!=files.end(); it++)
01329   {
01330     fileNames.push_back(it->string());
01331   }
01332   return fileNames;
01333 }
01334 
01335 void Driver::removeAllFiles()
01336 {
01337   boost::filesystem::path folderPath( boost::filesystem::current_path() );
01338   std::vector<boost::filesystem::path> files;
01339   helpers::filesystem::getFiles(folderPath, ".bag", files);
01340 
01341   for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
01342        it!=files.end(); it++)
01343   {
01344     std::remove(it->c_str());
01345   }
01346 }
01347 
01348 void Driver::removeFiles(std::vector<std::string> files)
01349 {
01350   for (std::vector<std::string>::const_iterator it=files.begin();
01351        it!=files.end(); it++)
01352   {
01353     std::remove(it->c_str());
01354   }
01355 }
01356 
01357 QI_REGISTER_OBJECT( Driver,
01358                     _whoIsYourDaddy,
01359                     minidump,
01360                     minidumpConverters,
01361                     setBufferDuration,
01362                     getBufferDuration,
01363                     startPublishing,
01364                     stopPublishing,
01365                     getMasterURI,
01366                     setMasterURI,
01367                     setMasterURINet,
01368                     getAvailableConverters,
01369                     getSubscribedPublishers,
01370                     addMemoryConverters,
01371                     registerMemoryConverter,
01372                     registerEventConverter,
01373                     getFilesList,
01374                     removeAllFiles,
01375                     removeFiles,
01376                     startRecording,
01377                     startRecordingConverters,
01378                     stopRecording,
01379                     startLogging,
01380                     stopLogging );
01381 } //naoqi


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