109 #include <boost/foreach.hpp>   110 #include <boost/property_tree/json_parser.hpp>   111 #define for_each BOOST_FOREACH   119   : sessionPtr_( session ),
   120   robot_( helpers::driver::
getRobot(session) ),
   122   publish_enabled_(false),
   123   record_enabled_(false),
   126   recorder_(
boost::make_shared<recorder::GlobalRecorder>(prefix)),
   131     std::cout << 
"Error driver prefix must not be empty" << std::endl;
   132     throw new ros::Exception(
"Error driver prefix must not be empty");
   142   std::cout << 
"naoqi driver is shutting down.." << std::endl;
   164   std::cout << 
"load boot config from " << file_path << std::endl;
   165   if (!file_path.empty())
   167     boost::property_tree::read_json( file_path, 
boot_config_ );
   181   static std::vector<message_actions::MessageAction> actions;
   213           boost::mutex::scoped_lock lock_record( 
mutex_record_, boost::try_to_lock );
   227         if (actions.size() >0)
   264     const std::string& err = 
"Log is not enabled, please enable logging before calling minidump";
   265     std::cout << 
BOLDRED << err << std::endl
   272   boost::filesystem::path folderPath(boost::filesystem::current_path());
   276     std::cout << 
BOLDRED << 
"No more space on robot. You need to upload the presents bags and remove them to make new ones."   277                  << std::endl << 
"To remove all the presents bags, you can run this command:" << std::endl
   278                     << 
"\t$ qicli call ROS-Driver.removeFiles" << 
RESETCOLOR << std::endl;
   279     return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
   292     iterator->second.isDumping(
true);
   303     iterator->second.writeDump(time);
   307     iterator->second.writeDump(time);
   314     iterator->second.isDumping(
false);
   323     const std::string& err = 
"Log is not enabled, please enable logging before calling minidump";
   324     std::cout << 
BOLDRED << err << std::endl
   331   boost::filesystem::path folderPath(boost::filesystem::current_path());
   335     std::cout << 
BOLDRED << 
"No more space on robot. You need to upload the presents bags and remove them to make new ones."   336                  << std::endl << 
"To remove all the presents bags, you can run this command:" << std::endl
   337                     << 
"\t$ qicli call ROS-Driver.removeFiles" << 
RESETCOLOR << std::endl;
   338     return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
   351     iterator->second.isDumping(
true);
   358   bool is_started = 
false;
   359   for_each( 
const std::string& name, names)
   369       it->second.writeDump(time);
   381         it_event->second.writeDump(time);
   389     iterator->second.isDumping(
false);
   397     std::cout << 
BOLDRED << 
"Could not find any topic in recorders" << 
RESETCOLOR << std::endl
   398       << 
BOLDYELLOW << 
"To get the list of all available converter's name, please run:" << 
RESETCOLOR << std::endl
   399       << 
GREEN << 
"\t$ qicli call ROS-Driver.getAvailableConverters" << 
RESETCOLOR << std::endl;
   400     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";
   408     iterator->second.setBufferDuration(duration);
   412     iterator->second.setBufferDuration(duration);
   438   pub_map_.insert( std::map<std::string, publisher::Publisher>::value_type(conv_name, pub) );
   446   rec_map_.insert( std::map<std::string, recorder::Recorder>::value_type(conv_name, rec) );
   453   event_map_.insert( std::map<std::string, event::Event>::value_type(key, event) );
   479     qi::AnyObject p_memory = 
sessionPtr_->service(
"ALMemory");
   480     value = p_memory.call<qi::AnyValue>(
"getData", key);
   481   } 
catch (
const std::exception& e) {
   482     std::cout << 
BOLDRED << 
"Could not get data in memory for the key: "   490     } 
catch (
const std::exception& e) {
   491       std::cout << 
BOLDRED << 
"Could not get a valid data type to register memory converter "   493                 << 
BOLDRED << 
"You can enter it yourself, available types are:" << std::endl
   494                 << 
"\t > 0 - None" << std::endl
   495                 << 
"\t > 1 - Float" << std::endl
   496                 << 
"\t > 2 - Int" << std::endl
   497                 << 
"\t > 3 - String" << std::endl
   498                 << 
"\t > 4 - Bool" << 
RESETCOLOR << std::endl;
   524       std::cout << 
BOLDRED << 
"Wrong data type. Available type are: " << std::endl
   525                    << 
"\t > 0 - None" << std::endl
   526                    << 
"\t > 1 - Float" << std::endl
   527                    << 
"\t > 2 - Int" << std::endl
   528                    << 
"\t > 3 - String" << std::endl
   529                    << 
"\t > 4 - Bool" << 
RESETCOLOR << std::endl;
   544   bool info_enabled                   = 
boot_config_.get( 
"converters.info.enabled", 
true);
   545   size_t info_frequency               = 
boot_config_.get( 
"converters.info.frequency", 1);
   547   bool audio_enabled                  = 
boot_config_.get( 
"converters.audio.enabled", 
true);
   548   size_t audio_frequency              = 
boot_config_.get( 
"converters.audio.frequency", 1);
   550   bool logs_enabled                   = 
boot_config_.get( 
"converters.logs.enabled", 
true);
   551   size_t logs_frequency               = 
boot_config_.get( 
"converters.logs.frequency", 10);
   553   bool diag_enabled                   = 
boot_config_.get( 
"converters.diag.enabled", 
true);
   554   size_t diag_frequency               = 
boot_config_.get( 
"converters.diag.frequency", 10);
   556   bool imu_torso_enabled              = 
boot_config_.get( 
"converters.imu_torso.enabled", 
true);
   557   size_t imu_torso_frequency          = 
boot_config_.get( 
"converters.imu_torso.frequency", 10);
   559   bool imu_base_enabled               = 
boot_config_.get( 
"converters.imu_base.enabled", 
true);
   560   size_t imu_base_frequency           = 
boot_config_.get( 
"converters.imu_base.frequency", 10);
   562   bool camera_front_enabled           = 
boot_config_.get( 
"converters.front_camera.enabled", 
true);
   563   size_t camera_front_resolution      = 
boot_config_.get( 
"converters.front_camera.resolution", 1); 
   564   size_t camera_front_fps             = 
boot_config_.get( 
"converters.front_camera.fps", 10);
   565   size_t camera_front_recorder_fps    = 
boot_config_.get( 
"converters.front_camera.recorder_fps", 5);
   567   bool camera_bottom_enabled          = 
boot_config_.get( 
"converters.bottom_camera.enabled", 
true);
   568   size_t camera_bottom_resolution     = 
boot_config_.get( 
"converters.bottom_camera.resolution", 1); 
   569   size_t camera_bottom_fps            = 
boot_config_.get( 
"converters.bottom_camera.fps", 10);
   570   size_t camera_bottom_recorder_fps   = 
boot_config_.get( 
"converters.bottom_camera.recorder_fps", 5);
   572   size_t camera_depth_resolution;
   573   bool camera_depth_enabled             = 
boot_config_.get( 
"converters.depth_camera.enabled", 
true);
   574   size_t camera_depth_xtion_resolution  = 
boot_config_.get( 
"converters.depth_camera.xtion_resolution", 1); 
   575   size_t camera_depth_stereo_resolution = 
boot_config_.get( 
"converters.depth_camera.stereo_resolution", 9); 
   576   size_t camera_depth_fps               = 
boot_config_.get( 
"converters.depth_camera.fps", 10);
   577   size_t camera_depth_recorder_fps      = 
boot_config_.get( 
"converters.depth_camera.recorder_fps", 5);
   579   bool camera_stereo_enabled          = 
boot_config_.get( 
"converters.stereo_camera.enabled", 
true);
   580   size_t camera_stereo_resolution     = 
boot_config_.get( 
"converters.stereo_camera.resolution", 15); 
   581   size_t camera_stereo_fps            = 
boot_config_.get( 
"converters.stereo_camera.fps", 10);
   582   size_t camera_stereo_recorder_fps    = 
boot_config_.get( 
"converters.stereo_camera.recorder_fps", 5);
   584   bool camera_ir_enabled              = 
boot_config_.get( 
"converters.ir_camera.enabled", 
true);
   585   size_t camera_ir_resolution         = 
boot_config_.get( 
"converters.ir_camera.resolution", 1); 
   586   size_t camera_ir_fps                = 
boot_config_.get( 
"converters.ir_camera.fps", 10);
   587   size_t camera_ir_recorder_fps       = 
boot_config_.get( 
"converters.ir_camera.recorder_fps", 5);
   589   bool joint_states_enabled           = 
boot_config_.get( 
"converters.joint_states.enabled", 
true);
   590   size_t joint_states_frequency       = 
boot_config_.get( 
"converters.joint_states.frequency", 50);
   592   bool laser_enabled                  = 
boot_config_.get( 
"converters.laser.enabled", 
true);
   593   size_t laser_frequency              = 
boot_config_.get( 
"converters.laser.frequency", 10);
   594   float laser_range_min              = 
boot_config_.get<
float>(
"converters.laser.range_min", 0.1);
   595   float laser_range_max              = 
boot_config_.get<
float>(
"converters.laser.range_max", 3.0);
   597   bool sonar_enabled                  = 
boot_config_.get( 
"converters.sonar.enabled", 
true);
   598   size_t sonar_frequency              = 
boot_config_.get( 
"converters.sonar.frequency", 10);
   600   bool odom_enabled                  = 
boot_config_.get( 
"converters.odom.enabled", 
true);
   601   size_t odom_frequency              = 
boot_config_.get( 
"converters.odom.frequency", 10);
   603   bool bumper_enabled                 = 
boot_config_.get( 
"converters.bumper.enabled", 
true);
   604   bool hand_enabled                   = 
boot_config_.get( 
"converters.touch_hand.enabled", 
true);
   605   bool head_enabled                   = 
boot_config_.get( 
"converters.touch_head.enabled", 
true);
   611       camera_ir_enabled = 
false;
   612       camera_depth_resolution = camera_depth_stereo_resolution;
   615       camera_depth_resolution = camera_depth_xtion_resolution;
   661   if ( imu_torso_enabled )
   675     if ( imu_base_enabled )
   688   if ( camera_front_enabled )
   700   if ( camera_bottom_enabled )
   715     if ( camera_depth_enabled )
   724         camera_depth_resolution,
   734     if (this->
has_stereo && camera_stereo_enabled)
   744         camera_stereo_resolution,
   754     if ( camera_ir_enabled )
   767   if ( joint_states_enabled )
   788       lc->setLaserRanges(laser_range_min, laser_range_max);
   799     std::vector<std::string> sonar_topics;
   802       sonar_topics.push_back(
"sonar/front");
   803       sonar_topics.push_back(
"sonar/back");
   807       sonar_topics.push_back(
"sonar/left");
   808       sonar_topics.push_back(
"sonar/right");
   819   if ( audio_enabled ) {
   822         boost::make_shared<AudioEventRegister>( 
"audio", 0, 
sessionPtr_ );
   825       event_map_.find(
"audio")->second.startProcess();
   828       event_map_.find(
"audio")->second.isPublishing(
true);
   833   if ( bumper_enabled )
   835     std::vector<std::string> bumper_events;
   836     bumper_events.push_back(
"RightBumperPressed");
   837     bumper_events.push_back(
"LeftBumperPressed");
   840       bumper_events.push_back(
"BackBumperPressed");
   843       boost::make_shared<BumperEventRegister>( 
"bumper", bumper_events, 0, 
sessionPtr_ );
   846       event_map_.find(
"bumper")->second.startProcess();
   849       event_map_.find(
"bumper")->second.isPublishing(
true);
   855     std::vector<std::string> hand_touch_events;
   856     hand_touch_events.push_back(
"HandRightBackTouched");
   857     hand_touch_events.push_back(
"HandRightLeftTouched");
   858     hand_touch_events.push_back(
"HandRightRightTouched");
   859     hand_touch_events.push_back(
"HandLeftBackTouched");
   860     hand_touch_events.push_back(
"HandLeftLeftTouched");
   861     hand_touch_events.push_back(
"HandLeftRightTouched");
   863       boost::make_shared<HandTouchEventRegister>( 
"hand_touch", hand_touch_events, 0, 
sessionPtr_ );
   866       event_map_.find(
"hand_touch")->second.startProcess();
   869       event_map_.find(
"hand_touch")->second.isPublishing(
true);
   875     std::vector<std::string> head_touch_events;
   876     head_touch_events.push_back(
"FrontTactilTouched");
   877     head_touch_events.push_back(
"MiddleTactilTouched");
   878     head_touch_events.push_back(
"RearTactilTouched");
   880       boost::make_shared<HeadTouchEventRegister>( 
"head_touch", head_touch_events, 0, 
sessionPtr_ );
   883       event_map_.find(
"head_touch")->second.startProcess();
   886       event_map_.find(
"head_touch")->second.isPublishing(
true);
   908   std::vector<subscriber::Subscriber>::iterator it;
   910   size_t sub_index = 0;
   918     std::cout << 
"registered subscriber:\t" << sub.
name() << std::endl;
   923     std::cout << 
"re-initialized existing subscriber:\t" << it->name() << std::endl;
   944   registerService( boost::make_shared<service::RobotConfigService>(
"get_robot_config", 
"/naoqi_driver/get_robot_config", 
sessionPtr_) );
   945   registerService( boost::make_shared<service::SetLanguageService>(
"set_language", 
"/naoqi_driver/set_language", 
sessionPtr_) );
   946   registerService( boost::make_shared<service::GetLanguageService>(
"get_language", 
"/naoqi_driver/get_language", 
sessionPtr_) );
   951   std::vector<std::string> conv_list;
   954     conv_list.push_back(conv.
name());
   958     conv_list.push_back( iterator->first );
   989     std::cout << 
"nodehandle reset " << std::endl;
   999     std::cout << 
BOLDRED << 
"going to register converters" << 
RESETCOLOR << std::endl;
  1006     std::cout << 
"NOT going to re-register the converters" << std::endl;
  1010     typedef std::map< std::string, publisher::Publisher > publisher_map;
  1013       pub.second.reset(*
nhPtr_);
  1028     typedef std::map< std::string, event::Event > event_map;
  1031       event.second.resetPublisher(*
nhPtr_);
  1039     std::cout << 
"going to start ROS loop" << std::endl;
  1049     iterator->second.isPublishing(
true);
  1058     iterator->second.isPublishing(
false);
  1064   std::vector<std::string> publisher;
  1070     if ( iterator->second.isSubscribed() )
  1072       publisher.push_back( iterator->second.topic() );
  1087       it->second.subscribe(
true);
  1095     iterator->second.isRecording(
true);
  1107   bool is_started = 
false;
  1108   for_each( 
const std::string& name, names)
  1119       it_rec->second.subscribe(
true);
  1131       it_ev->second.isRecording(
true);
  1138       std::cout << 
BOLDRED << 
"Could not find topic "  1141         << 
BOLDYELLOW << 
"To get the list of all available converter's name, please run:" << 
RESETCOLOR << std::endl
  1142         << 
GREEN << 
"\t$ qicli call ROS-Driver.getAvailableConverters" << 
RESETCOLOR << std::endl;
  1151     std::cout << 
BOLDRED << 
"Could not find any topic in recorders" << 
RESETCOLOR << std::endl
  1152       << 
BOLDYELLOW << 
"To get the list of all available converter's name, please run:" << 
RESETCOLOR << std::endl
  1153       << 
GREEN << 
"\t$ qicli call ROS-Driver.getAvailableConverters" << 
RESETCOLOR << std::endl;
  1166       it->second.subscribe(
false);
  1171     iterator->second.isRecording(
false);
  1192     iterator->second.startProcess();
  1205     iterator->second.stopProcess();
  1211   std::ifstream json_file;
  1212   json_file.open(filepath.c_str(), std::ios_base::in);
  1214   boost::property_tree::json_parser::read_json(json_file, pt);
  1221     std::cout << 
BOLDRED << 
"The connection with the ROS master does not seem to be initialized." << std::endl
  1223               << 
GREEN << 
"\t$ qicli call ROS-Driver.setMasterURI <YourROSCoreIP>" << 
RESETCOLOR << std::endl
  1229   boost::property_tree::ptree pt;
  1234   float frequency = 10.0f;
  1236     frequency = pt.get<
float>(
"frequency");
  1238   catch(
const boost::property_tree::ptree_bad_data& e){
  1239     std::cout << 
"\"frequency\" could not be interpreted as float: " <<  e.what() << std::endl;
  1240     std::cout << 
"Default to 10 Hz" << std::endl;
  1242   catch(
const boost::property_tree::ptree_bad_path& e){
  1243     std::cout << 
"\"frequency\" was not found: " <<  e.what() << std::endl;
  1244     std::cout << 
"Default to 10 Hz" << std::endl;
  1250     topic = pt.get<std::string>(
"topic");
  1252   catch(
const boost::property_tree::ptree_error& e){
  1253     std::cout << 
"\"topic\" could not be retrieved: " <<  e.what() << std::endl
  1254               << 
"Cannot add new converters" << std::endl;
  1258   std::vector<std::string> list;
  1260     BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child(
"memKeys"))
  1262       std::string topic = v.second.get_value<std::string>();
  1263       list.push_back(topic);
  1266   catch(
const boost::property_tree::ptree_error& e){
  1267     std::cout << 
"A problem occured during the reading of the mem keys list: " << e.what() << std::endl
  1268               << 
"Cannot add new converters" << std::endl;
  1273     std::cout << 
"The list of keys to add is empty. " << std::endl;
  1292     qi::AnyObject p_memory = 
sessionPtr_->service(
"ALMemory");
  1293     value = p_memory.call<qi::AnyValue>(
"getData", key);
  1294   } 
catch (
const std::exception& e) {
  1295     std::cout << 
BOLDRED << 
"Could not get data in memory for the key: "  1303     } 
catch (
const std::exception& e) {
  1304       std::cout << 
BOLDRED << 
"Could not get a valid data type to register memory converter "  1306                 << 
BOLDRED << 
"You can enter it yourself, available types are:" << std::endl
  1307                 << 
"\t > 0 - None" << std::endl
  1308                 << 
"\t > 1 - Float" << std::endl
  1309                 << 
"\t > 2 - Int" << std::endl
  1310                 << 
"\t > 3 - String" << std::endl
  1311                 << 
"\t > 4 - Bool" << 
RESETCOLOR << std::endl;
  1319   switch (data_type) {
  1353       std::cout << 
BOLDRED << 
"Wrong data type. Available type are: " << std::endl
  1354                    << 
"\t > 0 - None" << std::endl
  1355                    << 
"\t > 1 - Float" << std::endl
  1356                    << 
"\t > 2 - Int" << std::endl
  1357                    << 
"\t > 3 - String" << std::endl
  1358                    << 
"\t > 4 - Bool" << 
RESETCOLOR << std::endl;
  1367     event_map_.find(key)->second.isPublishing(
true);
  1375   std::vector<std::string> fileNames;
  1376   boost::filesystem::path folderPath( boost::filesystem::current_path() );
  1377   std::vector<boost::filesystem::path> files;
  1380   for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
  1381        it!=files.end(); it++)
  1383     fileNames.push_back(it->string());
  1390   boost::filesystem::path folderPath( boost::filesystem::current_path() );
  1391   std::vector<boost::filesystem::path> files;
  1394   for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
  1395        it!=files.end(); it++)
  1397     std::remove(it->c_str());
  1403   for (std::vector<std::string>::const_iterator it=files.begin();
  1404        it!=files.end(); it++)
  1406     std::remove(it->c_str());
 Converter concept interface. 
void publish(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
void bufferize(const std::vector< sensor_msgs::Range > &sonar_msgs)
void reset(ros::NodeHandle &nh)
initializes/resets the service into ROS with a given nodehandle, this will be called at first for ini...
static dataType::DataType getDataType(qi::AnyValue value)
std::map< std::string, recorder::Recorder >::iterator RecIter
void startPublishing()
qicli call function to start/enable publishing all registered publisher 
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
initializes/resets the recorder into ROS with a given nodehandle, this will be called at first for in...
void removeFiles(std::vector< std::string > files)
bool registerEventConverter(const std::string &key, const dataType::DataType &type)
qicli call function to register a converter for a given memory event 
void reset(ros::NodeHandle &nh)
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for i...
qi::SessionPtr sessionPtr_
std::vector< converter::Converter > converters_
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher 
Recorder concept interface. 
void bufferize(diagnostic_msgs::DiagnosticArray &msg)
QI_REGISTER_OBJECT(Driver, _whoIsYourDaddy, minidump, minidumpConverters, setBufferDuration, getBufferDuration, startPublishing, stopPublishing, getMasterURI, setMasterURI, setMasterURINet, getAvailableConverters, getSubscribedPublishers, addMemoryConverters, registerMemoryConverter, registerEventConverter, getFilesList, removeAllFiles, removeFiles, startRecording, startRecordingConverters, stopRecording, startLogging, stopLogging)
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
std::string name() const 
getting the descriptive name for this subscriber instance 
std::string name() const 
getting the descriptive name for this converter instance 
void getFiles(const boost::filesystem::path &root, const std::string &ext, std::vector< boost::filesystem::path > &ret)
static std::string prefix
void registerSubscriber(subscriber::Subscriber sub)
registers a subscriber 
void bufferize(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
std::string getMasterURI() const 
qicli call function to get current master uri 
std::vector< std::string > getSubscribedPublishers() const 
get all subscribed publishers 
void write(diagnostic_msgs::DiagnosticArray &msg)
Subscriber concept interface. 
void parseJsonFile(std::string filepath, boost::property_tree::ptree &pt)
boost::mutex mutex_conv_queue_
bool registerMemoryConverter(const std::string &key, float frequency, const dataType::DataType &type)
qicli call function to register a converter for a given memory key 
void registerDefaultConverter()
boost::property_tree::ptree boot_config_
static const long folderMaximumSize
virtual void publish(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
std::vector< subscriber::Subscriber > subscribers_
boost::scoped_ptr< ros::NodeHandle > nhPtr_
static void setPrefix(std::string s)
virtual void publish(const naoqi_bridge_msgs::StringStamped &msg)
boost::thread publisherThread_
Converter concept interface. 
std::string stopRecording()
qicli call function to stop recording all registered publisher in a ROSbag 
void stopPublishing()
qicli call function to stop/disable publishing all registered publisher 
Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is se...
Publisher concept interface. 
std::map< std::string, event::Event > event_map_
void registerDefaultServices()
std::map< std::string, publisher::Publisher >::const_iterator PubConstIter
float frequency() const 
getting the assigned frequency of this converter instance 
void write(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Driver(qi::SessionPtr session, const std::string &prefix)
Constructor for naoqi driver. 
static std::string getMasterURI()
void startRecording()
qicli call function to start recording all registered converter in a ROSbag 
static void setMasterURI(const std::string &uri, const std::string &network_interface)
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
const int kInfraredOrStereoCamera
static std::string getROSIP(std::string network_interface)
boost::shared_ptr< recorder::GlobalRecorder > recorder_
void callAll(const std::vector< message_actions::MessageAction > &actions)
bool isDepthStereo(const qi::SessionPtr &session)
static const float bufferDefaultDuration
boost::mutex mutex_record_
std::string minidump(const std::string &prefix)
Write a ROSbag with the last bufferized data (10s by default) 
std::vector< std::string > getFilesList()
void setMasterURI(const std::string &uri)
qicli call function to set current master uri 
const robot::Robot & robot_
std::priority_queue< ScheduledConverter > conv_queue_
std::string minidumpConverters(const std::string &prefix, const std::vector< std::string > &names)
~Driver()
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher. 
void addMemoryConverters(std::string filepath)
qicli call function to add on-the-fly some memory keys extractors 
void setMasterURINet(const std::string &uri, const std::string &network_interface)
qicli call function to set current master uri 
std::vector< service::Service > services_
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
void registerDefaultSubscriber()
std::vector< std::string > getAvailableConverters()
get all available converters 
const robot::Robot & getRobot(const qi::SessionPtr &session)
ROSCPP_DECL void shutdown()
std::string _whoIsYourDaddy()
void insertEventConverter(const std::string &key, event::Event event)
void registerRecorder(const std::string &conv_name, recorder::Recorder &rec, float frequency)
prepare and register a recorder 
void write(const std::vector< sensor_msgs::Range > &sonar_msgs)
std::map< std::string, event::Event >::const_iterator EventConstIter
std::map< std::string, recorder::Recorder >::const_iterator RecConstIter
void setBufferDuration(float duration)
void registerService(service::Service srv)
registers a service 
std::string & getBootConfigFile()
ROSCPP_DECL void spinOnce()
std::map< std::string, recorder::Recorder > rec_map_
void startRecordingConverters(const std::vector< std::string > &names)
qicli call function to start recording given topics in a ROSbag 
void publish(const std::vector< sensor_msgs::Range > &sonar_msgs)
void reset(ros::NodeHandle &nh)
initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for ...
std::map< std::string, event::Event >::iterator EventIter
void getFilesSize(const boost::filesystem::path &root, long &file_size)
float getBufferDuration()
Service concept interface. 
std::map< std::string, publisher::Publisher > pub_map_
void registerConverter(converter::Converter &conv)
registers generall converter units they are connected via callbacks to various actions such as record...