naoqi_driver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 /*
19  * PUBLIC INTERFACE
20  */
23 
24 /*
25  * CONVERTERS
26  */
27 #include "converters/audio.hpp"
28 #include "converters/touch.hpp"
29 #include "converters/camera.hpp"
31 #include "converters/imu.hpp"
32 #include "converters/info.hpp"
34 #include "converters/laser.hpp"
36 #include "converters/sonar.hpp"
41 #include "converters/log.hpp"
42 #include "converters/odom.hpp"
43 
44 /*
45  * PUBLISHERS
46  */
47 #include "publishers/basic.hpp"
48 #include "publishers/camera.hpp"
49 #include "publishers/info.hpp"
51 #include "publishers/log.hpp"
52 #include "publishers/sonar.hpp"
53 
54 /*
55  * TOOLS
56  */
58 #include "tools/alvisiondefinitions.h" // for kTop...
59 
60 /*
61  * SUBSCRIBERS
62  */
63 #include "subscribers/teleop.hpp"
64 #include "subscribers/moveto.hpp"
65 #include "subscribers/speech.hpp"
66 
67 
68 /*
69  * SERVICES
70  */
74 
75 /*
76  * RECORDERS
77  */
78 #include "recorder/basic.hpp"
79 #include "recorder/basic_event.hpp"
80 #include "recorder/camera.hpp"
81 #include "recorder/diagnostics.hpp"
82 #include "recorder/joint_state.hpp"
83 #include "recorder/sonar.hpp"
84 
85 /*
86  * EVENTS
87  */
88 #include "event/basic.hpp"
89 #include "event/audio.hpp"
90 #include "event/touch.hpp"
91 
92 /*
93  * STATIC FUNCTIONS INCLUDE
94  */
95 #include "ros_env.hpp"
100 
101 /*
102  * ROS
103  */
104 #include <tf2_ros/buffer.h>
105 
106 /*
107  * BOOST
108  */
109 #include <boost/foreach.hpp>
110 #include <boost/property_tree/json_parser.hpp>
111 #define for_each BOOST_FOREACH
112 
113 #define DEBUG 0
114 
115 namespace naoqi
116 {
117 
118 Driver::Driver( qi::SessionPtr session, const std::string& prefix )
119  : sessionPtr_( session ),
120  robot_( helpers::driver::getRobot(session) ),
121  freq_(15),
122  publish_enabled_(false),
123  record_enabled_(false),
124  log_enabled_(false),
125  keep_looping(true),
126  recorder_(boost::make_shared<recorder::GlobalRecorder>(prefix)),
127  buffer_duration_(helpers::recorder::bufferDefaultDuration),
128  has_stereo(helpers::driver::isDepthStereo(session))
129 {
130  if(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");
133  }
134  else {
136  }
137 
138 }
139 
141 {
142  std::cout << "naoqi driver is shutting down.." << std::endl;
143  // destroy nodehandle?
144  if(nhPtr_)
145  {
146  nhPtr_->shutdown();
147  ros::shutdown();
148  }
149 }
150 
152 {
153  ros::Time::init(); // can call this many times
154  loadBootConfig();
158  startRosLoop();
159 }
160 
162 {
163  const std::string& file_path = helpers::filesystem::getBootConfigFile();
164  std::cout << "load boot config from " << file_path << std::endl;
165  if (!file_path.empty())
166  {
167  boost::property_tree::read_json( file_path, boot_config_ );
168  }
169 }
170 
172  stopRosLoop();
173  converters_.clear();
174  subscribers_.clear();
175  event_map_.clear();
176 }
177 
178 
180 {
181  static std::vector<message_actions::MessageAction> actions;
182 
183 // ros::Time::init();
184  while( keep_looping )
185  {
186  // clear the callback triggers
187  actions.clear();
188  {
189  boost::mutex::scoped_lock lock( mutex_conv_queue_ );
190  if (!conv_queue_.empty())
191  {
192  // Wait for the next Publisher to be ready
193  size_t conv_index = conv_queue_.top().conv_index_;
194  converter::Converter& conv = converters_[conv_index];
195  ros::Time schedule = conv_queue_.top().schedule_;
196 
197  // check the publishing condition
198  // 1. publishing enabled
199  // 2. has to be registered
200  // 3. has to be subscribed
201  PubConstIter pub_it = pub_map_.find( conv.name() );
202  if ( publish_enabled_ && pub_it != pub_map_.end() && pub_it->second.isSubscribed() )
203  {
204  actions.push_back(message_actions::PUBLISH);
205  }
206 
207  // check the recording condition
208  // 1. recording enabled
209  // 2. has to be registered
210  // 3. has to be subscribed (configured to be recorded)
211  RecConstIter rec_it = rec_map_.find( conv.name() );
212  {
213  boost::mutex::scoped_lock lock_record( mutex_record_, boost::try_to_lock );
214  if ( lock_record && record_enabled_ && rec_it != rec_map_.end() && rec_it->second.isSubscribed() )
215  {
216  actions.push_back(message_actions::RECORD);
217  }
218  }
219 
220  // bufferize data in recorder
221  if ( log_enabled_ && rec_it != rec_map_.end() && conv.frequency() != 0)
222  {
223  actions.push_back(message_actions::LOG);
224  }
225 
226  // only call when we have at least one action to perform
227  if (actions.size() >0)
228  {
229  conv.callAll( actions );
230  }
231 
232  ros::Duration d( schedule - ros::Time::now() );
233  if ( d > ros::Duration(0))
234  {
235  d.sleep();
236  }
237 
238  // Schedule for a future time or not
239  conv_queue_.pop();
240  if ( conv.frequency() != 0 )
241  {
242  conv_queue_.push(ScheduledConverter(schedule + ros::Duration(1.0f / conv.frequency()), conv_index));
243  }
244 
245  }
246  else // conv_queue is empty.
247  {
248  // sleep one second
249  ros::Duration(1).sleep();
250  }
251  } // mutex scope
252 
253  if ( publish_enabled_ )
254  {
255  ros::spinOnce();
256  }
257  } // while loop
258 }
259 
260 std::string Driver::minidump(const std::string& prefix)
261 {
262  if (!log_enabled_)
263  {
264  const std::string& err = "Log is not enabled, please enable logging before calling minidump";
265  std::cout << BOLDRED << err << std::endl
266  << RESETCOLOR << std::endl;
267  return err;
268  }
269 
270  // CHECK SIZE IN FOLDER
271  long files_size = 0;
272  boost::filesystem::path folderPath(boost::filesystem::current_path());
273  helpers::filesystem::getFilesSize(folderPath, files_size);
275  {
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.";
280  }
281 
282  // IF A ROSBAG WAS OPENED, FIRST CLOSE IT
283  if (record_enabled_)
284  {
285  stopRecording();
286  }
287 
288  // STOP BUFFERIZING
289  log_enabled_ = false;
290  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
291  {
292  iterator->second.isDumping(true);
293  }
294  ros::Time time = ros::Time::now();
295 
296  // START A NEW ROSBAG
297  boost::mutex::scoped_lock lock_record( mutex_record_ );
298  recorder_->startRecord(prefix);
299 
300  // WRITE ALL BUFFER INTO THE ROSBAG
301  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
302  {
303  iterator->second.writeDump(time);
304  }
305  for(RecIter iterator = rec_map_.begin(); iterator != rec_map_.end(); iterator++)
306  {
307  iterator->second.writeDump(time);
308  }
309 
310  // RESTART BUFFERIZING
311  log_enabled_ = true;
312  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
313  {
314  iterator->second.isDumping(false);
315  }
316  return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
317 }
318 
319 std::string Driver::minidumpConverters(const std::string& prefix, const std::vector<std::string>& names)
320 {
321  if (!log_enabled_)
322  {
323  const std::string& err = "Log is not enabled, please enable logging before calling minidump";
324  std::cout << BOLDRED << err << std::endl
325  << RESETCOLOR << std::endl;
326  return err;
327  }
328 
329  // CHECK SIZE IN FOLDER
330  long files_size = 0;
331  boost::filesystem::path folderPath(boost::filesystem::current_path());
332  helpers::filesystem::getFilesSize(folderPath, files_size);
334  {
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.";
339  }
340 
341  // IF A ROSBAG WAS OPENED, FIRST CLOSE IT
342  if (record_enabled_)
343  {
344  stopRecording();
345  }
346 
347  // STOP BUFFERIZING
348  log_enabled_ = false;
349  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
350  {
351  iterator->second.isDumping(true);
352  }
353  ros::Time time = ros::Time::now();
354 
355  // WRITE CHOOSEN BUFFER INTO THE ROSBAG
356  boost::mutex::scoped_lock lock_record( mutex_record_ );
357 
358  bool is_started = false;
359  for_each( const std::string& name, names)
360  {
361  RecIter it = rec_map_.find(name);
362  if ( it != rec_map_.end() )
363  {
364  if ( !is_started )
365  {
366  recorder_->startRecord(prefix);
367  is_started = true;
368  }
369  it->second.writeDump(time);
370  }
371  else
372  {
373  EventIter it_event = event_map_.find(name);
374  if ( it_event != event_map_.end() )
375  {
376  if ( !is_started )
377  {
378  recorder_->startRecord(prefix);
379  is_started = true;
380  }
381  it_event->second.writeDump(time);
382  }
383  }
384  }
385  // RESTART BUFFERIZING
386  log_enabled_ = true;
387  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
388  {
389  iterator->second.isDumping(false);
390  }
391  if ( is_started )
392  {
393  return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
394  }
395  else
396  {
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";
401  }
402 }
403 
404 void Driver::setBufferDuration(float duration)
405 {
406  for(RecIter iterator = rec_map_.begin(); iterator != rec_map_.end(); iterator++)
407  {
408  iterator->second.setBufferDuration(duration);
409  }
410  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
411  {
412  iterator->second.setBufferDuration(duration);
413  }
414  buffer_duration_ = duration;
415 }
416 
418 {
419  return buffer_duration_;
420 }
421 
423 {
424  boost::mutex::scoped_lock lock( mutex_conv_queue_ );
425  int conv_index = converters_.size();
426  converters_.push_back( conv );
427  conv.reset();
428  conv_queue_.push(ScheduledConverter(ros::Time::now(), conv_index));
429 }
430 
431 void Driver::registerPublisher( const std::string& conv_name, publisher::Publisher& pub)
432 {
433  if (publish_enabled_) {
434  pub.reset(*nhPtr_);
435  }
436  // Concept classes don't have any default constructors needed by operator[]
437  // Cannot use this operator here. So we use insert
438  pub_map_.insert( std::map<std::string, publisher::Publisher>::value_type(conv_name, pub) );
439 }
440 
441 void Driver::registerRecorder( const std::string& conv_name, recorder::Recorder& rec, float frequency)
442 {
443  // Concept classes don't have any default constructors needed by operator[]
444  // Cannot use this operator here. So we use insert
445  rec.reset(recorder_, frequency);
446  rec_map_.insert( std::map<std::string, recorder::Recorder>::value_type(conv_name, rec) );
447 }
448 
449 void Driver::insertEventConverter(const std::string& key, event::Event event)
450 {
451  //event.reset(*nhPtr_, recorder_);
452  event.resetRecorder(recorder_);
453  event_map_.insert( std::map<std::string, event::Event>::value_type(key, event) );
454 }
455 
457 {
458  registerConverter( conv );
459  registerPublisher( conv.name(), pub);
460  registerRecorder( conv.name(), rec, conv.frequency());
461 }
462 
464 {
465  registerConverter( conv );
466  registerPublisher(conv.name(), pub);
467 }
468 
470 {
471  registerConverter( conv );
472  registerRecorder( conv.name(), rec, conv.frequency());
473 }
474 
475 bool Driver::registerMemoryConverter( const std::string& key, float frequency, const dataType::DataType& type ) {
476  dataType::DataType data_type;
477  qi::AnyValue value;
478  try {
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: "
483  << BOLDCYAN << key << RESETCOLOR << std::endl;
484  return false;
485  }
486 
487  if (type==dataType::None) {
488  try {
489  data_type = helpers::naoqi::getDataType(value);
490  } catch (const std::exception& e) {
491  std::cout << BOLDRED << "Could not get a valid data type to register memory converter "
492  << BOLDCYAN << key << RESETCOLOR << std::endl
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;
499  return false;
500  }
501  }
502  else {
503  data_type = type;
504  }
505 
506  switch (data_type) {
507  case 0:
508  return false;
509  break;
510  case 1:
511  _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::FloatStamped>,converter::MemoryFloatConverter>(key,frequency);
512  break;
513  case 2:
514  _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::IntStamped>,converter::MemoryIntConverter>(key,frequency);
515  break;
516  case 3:
517  _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped>,converter::MemoryStringConverter>(key,frequency);
518  break;
519  case 4:
520  _registerMemoryConverter<publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicRecorder<naoqi_bridge_msgs::BoolStamped>,converter::MemoryBoolConverter>(key,frequency);
521  break;
522  default:
523  {
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;
530  return false;
531  break;
532  }
533  }
534  return true;
535 }
536 
538 {
539  // init global tf2 buffer
541  tf2_buffer_->setUsingDedicatedThread(true);
542 
543  // replace this with proper configuration struct
544  bool info_enabled = boot_config_.get( "converters.info.enabled", true);
545  size_t info_frequency = boot_config_.get( "converters.info.frequency", 1);
546 
547  bool audio_enabled = boot_config_.get( "converters.audio.enabled", true);
548  size_t audio_frequency = boot_config_.get( "converters.audio.frequency", 1);
549 
550  bool logs_enabled = boot_config_.get( "converters.logs.enabled", true);
551  size_t logs_frequency = boot_config_.get( "converters.logs.frequency", 10);
552 
553  bool diag_enabled = boot_config_.get( "converters.diag.enabled", true);
554  size_t diag_frequency = boot_config_.get( "converters.diag.frequency", 10);
555 
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);
558 
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);
561 
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); // VGA
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);
566 
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); // VGA
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);
571 
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); // QVGA
575  size_t camera_depth_stereo_resolution = boot_config_.get( "converters.depth_camera.stereo_resolution", 9); // Q720p
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);
578 
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); // QQ720px2
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);
583 
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); // QVGA
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);
588 
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);
591 
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);
596 
597  bool sonar_enabled = boot_config_.get( "converters.sonar.enabled", true);
598  size_t sonar_frequency = boot_config_.get( "converters.sonar.frequency", 10);
599 
600  bool odom_enabled = boot_config_.get( "converters.odom.enabled", true);
601  size_t odom_frequency = boot_config_.get( "converters.odom.frequency", 10);
602 
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);
606 
607  // Load the correct variables depending on the type of the depth camera
608  // (XTION or stereo). IR disabled if the robot uses a stereo camera to
609  // compute the depth
610  if (this->has_stereo) {
611  camera_ir_enabled = false;
612  camera_depth_resolution = camera_depth_stereo_resolution;
613  }
614  else {
615  camera_depth_resolution = camera_depth_xtion_resolution;
616  }
617 
618  /*
619  * The info converter will be called once after it was added to the priority queue. Once it is its turn to be called, its
620  * callAll method will be triggered (because InfoPublisher is considered to always have subscribers, isSubscribed always
621  * return true).
622  * A message is therefore published through InfoPublisher, even if there is nobody to receive it.
623  * Then, InfoConverter will never be called again, because of its 0Hz frequency. But if a new user subscribes to the "info"
624  * topic, he/she will receive the information published before, as the publisher is latched.
625  */
627  if ( info_enabled )
628  {
629  boost::shared_ptr<publisher::InfoPublisher> inp = boost::make_shared<publisher::InfoPublisher>( "info" , robot_);
630  boost::shared_ptr<recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped> > inr = boost::make_shared<recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped> >( "info" );
631  boost::shared_ptr<converter::InfoConverter> inc = boost::make_shared<converter::InfoConverter>( "info", 0, sessionPtr_ );
632  inc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::InfoPublisher::publish, inp, _1) );
633  inc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::StringStamped>::write, inr, _1) );
635  registerConverter( inc, inp, inr );
636  }
637 
638 
640  if ( logs_enabled )
641  {
642  boost::shared_ptr<converter::LogConverter> lc = boost::make_shared<converter::LogConverter>( "log", logs_frequency, sessionPtr_);
643  boost::shared_ptr<publisher::LogPublisher> lp = boost::make_shared<publisher::LogPublisher>( "/rosout" );
644  lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::LogPublisher::publish, lp, _1) );
645  registerPublisher( lc, lp );
646  }
647 
649  if ( diag_enabled )
650  {
651  boost::shared_ptr<converter::DiagnosticsConverter> dc = boost::make_shared<converter::DiagnosticsConverter>( "diag", diag_frequency, sessionPtr_);
652  boost::shared_ptr<publisher::BasicPublisher<diagnostic_msgs::DiagnosticArray> > dp = boost::make_shared<publisher::BasicPublisher<diagnostic_msgs::DiagnosticArray> >( "/diagnostics" );
653  boost::shared_ptr<recorder::DiagnosticsRecorder> dr = boost::make_shared<recorder::DiagnosticsRecorder>( "/diagnostics" );
655  dc->registerCallback( message_actions::RECORD, boost::bind(&recorder::DiagnosticsRecorder::write, dr, _1) );
656  dc->registerCallback( message_actions::LOG, boost::bind(&recorder::DiagnosticsRecorder::bufferize, dr, _1) );
657  registerConverter( dc, dp, dr );
658  }
659 
661  if ( imu_torso_enabled )
662  {
663  boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::Imu> > imutp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::Imu> >( "imu/torso" );
664  boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::Imu> > imutr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::Imu> >( "imu/torso" );
665  boost::shared_ptr<converter::ImuConverter> imutc = boost::make_shared<converter::ImuConverter>( "imu_torso", converter::IMU::TORSO, imu_torso_frequency, sessionPtr_);
666  imutc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::Imu>::publish, imutp, _1) );
667  imutc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::write, imutr, _1) );
668  imutc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::bufferize, imutr, _1) );
669  registerConverter( imutc, imutp, imutr );
670  }
671 
672  if(robot_ == robot::PEPPER)
673  {
675  if ( imu_base_enabled )
676  {
677  boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::Imu> > imubp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::Imu> >( "imu/base" );
678  boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::Imu> > imubr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::Imu> >( "imu/base" );
679  boost::shared_ptr<converter::ImuConverter> imubc = boost::make_shared<converter::ImuConverter>( "imu_base", converter::IMU::BASE, imu_base_frequency, sessionPtr_);
680  imubc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::Imu>::publish, imubp, _1) );
681  imubc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::write, imubr, _1) );
682  imubc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::Imu>::bufferize, imubr, _1) );
683  registerConverter( imubc, imubp, imubr );
684  }
685  } // endif PEPPER
686 
688  if ( camera_front_enabled )
689  {
690  boost::shared_ptr<publisher::CameraPublisher> fcp = boost::make_shared<publisher::CameraPublisher>( "camera/front/image_raw", AL::kTopCamera );
691  boost::shared_ptr<recorder::CameraRecorder> fcr = boost::make_shared<recorder::CameraRecorder>( "camera/front", camera_front_recorder_fps );
692  boost::shared_ptr<converter::CameraConverter> fcc = boost::make_shared<converter::CameraConverter>( "front_camera", camera_front_fps, sessionPtr_, AL::kTopCamera, camera_front_resolution );
693  fcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, fcp, _1, _2) );
694  fcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, fcr, _1, _2) );
695  fcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, fcr, _1, _2) );
696  registerConverter( fcc, fcp, fcr );
697  }
698 
700  if ( camera_bottom_enabled )
701  {
702  boost::shared_ptr<publisher::CameraPublisher> bcp = boost::make_shared<publisher::CameraPublisher>( "camera/bottom/image_raw", AL::kBottomCamera );
703  boost::shared_ptr<recorder::CameraRecorder> bcr = boost::make_shared<recorder::CameraRecorder>( "camera/bottom", camera_bottom_recorder_fps );
704  boost::shared_ptr<converter::CameraConverter> bcc = boost::make_shared<converter::CameraConverter>( "bottom_camera", camera_bottom_fps, sessionPtr_, AL::kBottomCamera, camera_bottom_resolution );
705  bcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, bcp, _1, _2) );
706  bcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, bcr, _1, _2) );
707  bcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, bcr, _1, _2) );
708  registerConverter( bcc, bcp, bcr );
709  }
710 
711 
712  if(robot_ == robot::PEPPER)
713  {
715  if ( camera_depth_enabled )
716  {
717  boost::shared_ptr<publisher::CameraPublisher> dcp = boost::make_shared<publisher::CameraPublisher>( "camera/depth/image_raw", AL::kDepthCamera );
718  boost::shared_ptr<recorder::CameraRecorder> dcr = boost::make_shared<recorder::CameraRecorder>( "camera/depth", camera_depth_recorder_fps );
719  boost::shared_ptr<converter::CameraConverter> dcc = boost::make_shared<converter::CameraConverter>(
720  "depth_camera",
721  camera_depth_fps,
722  sessionPtr_,
724  camera_depth_resolution,
725  this->has_stereo);
726 
727  dcc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, dcp, _1, _2) );
728  dcc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, dcr, _1, _2) );
729  dcc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, dcr, _1, _2) );
730  registerConverter( dcc, dcp, dcr );
731  }
732 
734  if (this->has_stereo && camera_stereo_enabled)
735  {
736  boost::shared_ptr<publisher::CameraPublisher> scp = boost::make_shared<publisher::CameraPublisher>( "camera/stereo/image_raw", AL::kInfraredOrStereoCamera );
737  boost::shared_ptr<recorder::CameraRecorder> scr = boost::make_shared<recorder::CameraRecorder>( "camera/stereo", camera_stereo_recorder_fps );
738 
739  boost::shared_ptr<converter::CameraConverter> scc = boost::make_shared<converter::CameraConverter>(
740  "stereo_camera",
741  camera_stereo_fps,
742  sessionPtr_,
744  camera_stereo_resolution,
745  this->has_stereo);
746 
747  scc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, scp, _1, _2) );
748  scc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, scr, _1, _2) );
749  scc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, scr, _1, _2) );
750  registerConverter( scc, scp, scr );
751  }
752 
754  if ( camera_ir_enabled )
755  {
756  boost::shared_ptr<publisher::CameraPublisher> icp = boost::make_shared<publisher::CameraPublisher>( "camera/ir/image_raw", AL::kInfraredOrStereoCamera );
757  boost::shared_ptr<recorder::CameraRecorder> icr = boost::make_shared<recorder::CameraRecorder>( "camera/ir", camera_ir_recorder_fps );
758  boost::shared_ptr<converter::CameraConverter> icc = boost::make_shared<converter::CameraConverter>( "infrared_camera", camera_ir_fps, sessionPtr_, AL::kInfraredOrStereoCamera, camera_ir_resolution);
759  icc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::CameraPublisher::publish, icp, _1, _2) );
760  icc->registerCallback( message_actions::RECORD, boost::bind(&recorder::CameraRecorder::write, icr, _1, _2) );
761  icc->registerCallback( message_actions::LOG, boost::bind(&recorder::CameraRecorder::bufferize, icr, _1, _2) );
762  registerConverter( icc, icp, icr );
763  }
764  } // endif PEPPER
765 
767  if ( joint_states_enabled )
768  {
769  boost::shared_ptr<publisher::JointStatePublisher> jsp = boost::make_shared<publisher::JointStatePublisher>( "/joint_states" );
770  boost::shared_ptr<recorder::JointStateRecorder> jsr = boost::make_shared<recorder::JointStateRecorder>( "/joint_states" );
771  boost::shared_ptr<converter::JointStateConverter> jsc = boost::make_shared<converter::JointStateConverter>( "joint_states", joint_states_frequency, tf2_buffer_, sessionPtr_ );
772  jsc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::JointStatePublisher::publish, jsp, _1, _2) );
773  jsc->registerCallback( message_actions::RECORD, boost::bind(&recorder::JointStateRecorder::write, jsr, _1, _2) );
774  jsc->registerCallback( message_actions::LOG, boost::bind(&recorder::JointStateRecorder::bufferize, jsr, _1, _2) );
775  registerConverter( jsc, jsp, jsr );
776  // registerRecorder(jsc, jsr);
777  }
778 
779  if(robot_ == robot::PEPPER)
780  {
782  if ( laser_enabled )
783  {
784  boost::shared_ptr<publisher::BasicPublisher<sensor_msgs::LaserScan> > lp = boost::make_shared<publisher::BasicPublisher<sensor_msgs::LaserScan> >( "laser" );
785  boost::shared_ptr<recorder::BasicRecorder<sensor_msgs::LaserScan> > lr = boost::make_shared<recorder::BasicRecorder<sensor_msgs::LaserScan> >( "laser" );
786  boost::shared_ptr<converter::LaserConverter> lc = boost::make_shared<converter::LaserConverter>( "laser", laser_frequency, sessionPtr_ );
787 
788  lc->setLaserRanges(laser_range_min, laser_range_max);
789  lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<sensor_msgs::LaserScan>::publish, lp, _1) );
790  lc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<sensor_msgs::LaserScan>::write, lr, _1) );
791  lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<sensor_msgs::LaserScan>::bufferize, lr, _1) );
792  registerConverter( lc, lp, lr );
793  }
794  }
795 
797  if ( sonar_enabled )
798  {
799  std::vector<std::string> sonar_topics;
800  if (robot_ == robot::PEPPER)
801  {
802  sonar_topics.push_back("sonar/front");
803  sonar_topics.push_back("sonar/back");
804  }
805  else
806  {
807  sonar_topics.push_back("sonar/left");
808  sonar_topics.push_back("sonar/right");
809  }
810  boost::shared_ptr<publisher::SonarPublisher> usp = boost::make_shared<publisher::SonarPublisher>( sonar_topics );
811  boost::shared_ptr<recorder::SonarRecorder> usr = boost::make_shared<recorder::SonarRecorder>( sonar_topics );
812  boost::shared_ptr<converter::SonarConverter> usc = boost::make_shared<converter::SonarConverter>( "sonar", sonar_frequency, sessionPtr_ );
813  usc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::SonarPublisher::publish, usp, _1) );
814  usc->registerCallback( message_actions::RECORD, boost::bind(&recorder::SonarRecorder::write, usr, _1) );
815  usc->registerCallback( message_actions::LOG, boost::bind(&recorder::SonarRecorder::bufferize, usr, _1) );
816  registerConverter( usc, usp, usr );
817  }
818 
819  if ( audio_enabled ) {
822  boost::make_shared<AudioEventRegister>( "audio", 0, sessionPtr_ );
823  insertEventConverter("audio", event_register);
824  if (keep_looping) {
825  event_map_.find("audio")->second.startProcess();
826  }
827  if (publish_enabled_) {
828  event_map_.find("audio")->second.isPublishing(true);
829  }
830  }
831 
833  if ( bumper_enabled )
834  {
835  std::vector<std::string> bumper_events;
836  bumper_events.push_back("RightBumperPressed");
837  bumper_events.push_back("LeftBumperPressed");
838  if (robot_ == robot::PEPPER)
839  {
840  bumper_events.push_back("BackBumperPressed");
841  }
843  boost::make_shared<BumperEventRegister>( "bumper", bumper_events, 0, sessionPtr_ );
844  insertEventConverter("bumper", event_register);
845  if (keep_looping) {
846  event_map_.find("bumper")->second.startProcess();
847  }
848  if (publish_enabled_) {
849  event_map_.find("bumper")->second.isPublishing(true);
850  }
851  }
852 
853  if ( hand_enabled )
854  {
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_ );
864  insertEventConverter("hand_touch", event_register);
865  if (keep_looping) {
866  event_map_.find("hand_touch")->second.startProcess();
867  }
868  if (publish_enabled_) {
869  event_map_.find("hand_touch")->second.isPublishing(true);
870  }
871  }
872 
873  if ( head_enabled )
874  {
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_ );
881  insertEventConverter("head_touch", event_register);
882  if (keep_looping) {
883  event_map_.find("head_touch")->second.startProcess();
884  }
885  if (publish_enabled_) {
886  event_map_.find("head_touch")->second.isPublishing(true);
887  }
888  }
889 
891  if ( odom_enabled )
892  {
893  boost::shared_ptr<publisher::BasicPublisher<nav_msgs::Odometry> > lp = boost::make_shared<publisher::BasicPublisher<nav_msgs::Odometry> >( "odom" );
894  boost::shared_ptr<recorder::BasicRecorder<nav_msgs::Odometry> > lr = boost::make_shared<recorder::BasicRecorder<nav_msgs::Odometry> >( "odom" );
895  boost::shared_ptr<converter::OdomConverter> lc = boost::make_shared<converter::OdomConverter>( "odom", odom_frequency, sessionPtr_ );
896  lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<nav_msgs::Odometry>::publish, lp, _1) );
897  lc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::write, lr, _1) );
898  lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::bufferize, lr, _1) );
899  registerConverter( lc, lp, lr );
900  }
901 
902 }
903 
904 
905 // public interface here
907 {
908  std::vector<subscriber::Subscriber>::iterator it;
909  it = std::find( subscribers_.begin(), subscribers_.end(), sub );
910  size_t sub_index = 0;
911 
912  // if subscriber is not found, register it!
913  if (it == subscribers_.end() )
914  {
915  sub_index = subscribers_.size();
916  //sub.reset( *nhPtr_ );
917  subscribers_.push_back( sub );
918  std::cout << "registered subscriber:\t" << sub.name() << std::endl;
919  }
920  // if found, re-init them
921  else
922  {
923  std::cout << "re-initialized existing subscriber:\t" << it->name() << std::endl;
924  }
925 }
926 
928 {
929  if (!subscribers_.empty())
930  return;
931  registerSubscriber( boost::make_shared<naoqi::subscriber::TeleopSubscriber>("teleop", "/cmd_vel", "/joint_angles", sessionPtr_) );
932  registerSubscriber( boost::make_shared<naoqi::subscriber::MovetoSubscriber>("moveto", "/move_base_simple/goal", sessionPtr_, tf2_buffer_) );
933  registerSubscriber( boost::make_shared<naoqi::subscriber::SpeechSubscriber>("speech", "/speech", sessionPtr_) );
934 }
935 
937 {
938  services_.push_back( srv );
939 }
940 
941 
943 {
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_) );
947 }
948 
949 std::vector<std::string> Driver::getAvailableConverters()
950 {
951  std::vector<std::string> conv_list;
953  {
954  conv_list.push_back(conv.name());
955  }
956  for(EventConstIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
957  {
958  conv_list.push_back( iterator->first );
959  }
960 
961  return conv_list;
962 }
963 
964 /*
965 * EXPOSED FUNCTIONS
966 */
967 
968 std::string Driver::getMasterURI() const
969 {
970  return ros_env::getMasterURI();
971 }
972 
973 void Driver::setMasterURI( const std::string& uri)
974 {
975  setMasterURINet(uri, "eth0");
976 }
977 
978 void Driver::setMasterURINet( const std::string& uri, const std::string& network_interface)
979 {
980  // To avoid two calls to this function happening at the same time
981  boost::mutex::scoped_lock lock( mutex_conv_queue_ );
982 
983  // Stopping the loop if there is any
984  //stopRosLoop();
985 
986  // Reinitializing ROS Node
987  {
988  nhPtr_.reset();
989  std::cout << "nodehandle reset " << std::endl;
990  ros_env::setMasterURI( uri, network_interface );
991  nhPtr_.reset( new ros::NodeHandle("~") );
992  }
993 
994  if(converters_.empty())
995  {
996  // If there is no converters, create them
997  // (converters only depends on Naoqi, resetting the
998  // Ros node has no impact on them)
999  std::cout << BOLDRED << "going to register converters" << RESETCOLOR << std::endl;
1002 // startRosLoop();
1003  }
1004  else
1005  {
1006  std::cout << "NOT going to re-register the converters" << std::endl;
1007  // If some converters are already there, then
1008  // we just need to reset the registered publisher
1009  // using the new ROS node handler.
1010  typedef std::map< std::string, publisher::Publisher > publisher_map;
1011  for_each( publisher_map::value_type &pub, pub_map_ )
1012  {
1013  pub.second.reset(*nhPtr_);
1014  }
1015 
1017  {
1018  sub.reset( *nhPtr_ );
1019  }
1020 
1022  {
1023  srv.reset( *nhPtr_ );
1024  }
1025  }
1026 
1027  if (!event_map_.empty()) {
1028  typedef std::map< std::string, event::Event > event_map;
1029  for_each( event_map::value_type &event, event_map_ )
1030  {
1031  event.second.resetPublisher(*nhPtr_);
1032  }
1033  }
1034  // Start publishing again
1035  startPublishing();
1036 
1037  if ( !keep_looping )
1038  {
1039  std::cout << "going to start ROS loop" << std::endl;
1040  startRosLoop();
1041  }
1042 }
1043 
1045 {
1046  publish_enabled_ = true;
1047  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1048  {
1049  iterator->second.isPublishing(true);
1050  }
1051 }
1052 
1054 {
1055  publish_enabled_ = false;
1056  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1057  {
1058  iterator->second.isPublishing(false);
1059  }
1060 }
1061 
1062 std::vector<std::string> Driver::getSubscribedPublishers() const
1063 {
1064  std::vector<std::string> publisher;
1065  for(PubConstIter iterator = pub_map_.begin(); iterator != pub_map_.end(); iterator++)
1066  {
1067  // iterator->first = key
1068  // iterator->second = value
1069  // Repeat if you also want to iterate through the second map.
1070  if ( iterator->second.isSubscribed() )
1071  {
1072  publisher.push_back( iterator->second.topic() );
1073  }
1074  }
1075  return publisher;
1076 }
1077 
1079 {
1080  boost::mutex::scoped_lock lock_record( mutex_record_ );
1081  recorder_->startRecord();
1083  {
1084  RecIter it = rec_map_.find(conv.name());
1085  if ( it != rec_map_.end() )
1086  {
1087  it->second.subscribe(true);
1088  std::cout << HIGHGREEN << "Topic "
1089  << BOLDCYAN << conv.name() << RESETCOLOR
1090  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1091  }
1092  }
1093  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1094  {
1095  iterator->second.isRecording(true);
1096  std::cout << HIGHGREEN << "Topic "
1097  << BOLDCYAN << iterator->first << RESETCOLOR
1098  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1099  }
1100  record_enabled_ = true;
1101 }
1102 
1103 void Driver::startRecordingConverters(const std::vector<std::string>& names)
1104 {
1105  boost::mutex::scoped_lock lock_record( mutex_record_ );
1106 
1107  bool is_started = false;
1108  for_each( const std::string& name, names)
1109  {
1110  RecIter it_rec = rec_map_.find(name);
1111  EventIter it_ev = event_map_.find(name);
1112  if ( it_rec != rec_map_.end() )
1113  {
1114  if ( !is_started )
1115  {
1116  recorder_->startRecord();
1117  is_started = true;
1118  }
1119  it_rec->second.subscribe(true);
1120  std::cout << HIGHGREEN << "Topic "
1121  << BOLDCYAN << name << RESETCOLOR
1122  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1123  }
1124  else if ( it_ev != event_map_.end() )
1125  {
1126  if ( !is_started )
1127  {
1128  recorder_->startRecord();
1129  is_started = true;
1130  }
1131  it_ev->second.isRecording(true);
1132  std::cout << HIGHGREEN << "Topic "
1133  << BOLDCYAN << name << RESETCOLOR
1134  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1135  }
1136  else
1137  {
1138  std::cout << BOLDRED << "Could not find topic "
1139  << BOLDCYAN << name
1140  << BOLDRED << " in recorders" << RESETCOLOR << std::endl
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;
1143  }
1144  }
1145  if ( is_started )
1146  {
1147  record_enabled_ = true;
1148  }
1149  else
1150  {
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;
1154  }
1155 }
1156 
1158 {
1159  boost::mutex::scoped_lock lock_record( mutex_record_ );
1160  record_enabled_ = false;
1162  {
1163  RecIter it = rec_map_.find(conv.name());
1164  if ( it != rec_map_.end() )
1165  {
1166  it->second.subscribe(false);
1167  }
1168  }
1169  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1170  {
1171  iterator->second.isRecording(false);
1172  }
1173  return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
1174 }
1175 
1177 {
1178  log_enabled_ = true;
1179 }
1180 
1182 {
1183  log_enabled_ = false;
1184 }
1185 
1187 {
1188  if (publisherThread_.get_id() == boost::thread::id())
1189  publisherThread_ = boost::thread( &Driver::rosLoop, this );
1190  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1191  {
1192  iterator->second.startProcess();
1193  }
1194  // Create the publishing thread if needed
1195  keep_looping = true;
1196 }
1197 
1199 {
1200  keep_looping = false;
1201  if (publisherThread_.get_id() != boost::thread::id())
1202  publisherThread_.join();
1203  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1204  {
1205  iterator->second.stopProcess();
1206  }
1207 }
1208 
1209 void Driver::parseJsonFile(std::string filepath, boost::property_tree::ptree &pt){
1210  // Open json file and parse it
1211  std::ifstream json_file;
1212  json_file.open(filepath.c_str(), std::ios_base::in);
1213 
1214  boost::property_tree::json_parser::read_json(json_file, pt);
1215  json_file.close();
1216 }
1217 
1218 void Driver::addMemoryConverters(std::string filepath){
1219  // Check if the nodeHandle pointer is already initialized
1220  if(!nhPtr_){
1221  std::cout << BOLDRED << "The connection with the ROS master does not seem to be initialized." << std::endl
1222  << BOLDYELLOW << "Please run:" << RESETCOLOR << std::endl
1223  << GREEN << "\t$ qicli call ROS-Driver.setMasterURI <YourROSCoreIP>" << RESETCOLOR << std::endl
1224  << BOLDYELLOW << "before trying to add converters" << RESETCOLOR << std::endl;
1225  return;
1226  }
1227 
1228  // Open the file filepath and parse it
1229  boost::property_tree::ptree pt;
1230  parseJsonFile(filepath, pt);
1231 
1232 
1233  // Get the frequency requested (default to 10 Hz)
1234  float frequency = 10.0f;
1235  try{
1236  frequency = pt.get<float>("frequency");
1237  }
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;
1241  }
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;
1245  }
1246 
1247  // Get the topic name requested
1248  std::string topic;
1249  try{
1250  topic = pt.get<std::string>("topic");
1251  }
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;
1255  return;
1256  }
1257 
1258  std::vector<std::string> list;
1259  try{
1260  BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child("memKeys"))
1261  {
1262  std::string topic = v.second.get_value<std::string>();
1263  list.push_back(topic);
1264  }
1265  }
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;
1269  return;
1270  }
1271 
1272  if(list.empty()){
1273  std::cout << "The list of keys to add is empty. " << std::endl;
1274  return;
1275  }
1276 
1277  // Create converter, publisher and recorder
1278  boost::shared_ptr<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> > mlp = boost::make_shared<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> >( topic );
1279  boost::shared_ptr<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> > mlr = boost::make_shared<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> >( topic );
1280  boost::shared_ptr<converter::MemoryListConverter> mlc = boost::make_shared<converter::MemoryListConverter>(list, topic, frequency, sessionPtr_ );
1282  mlc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::write, mlr, _1) );
1283  mlc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::bufferize, mlr, _1) );
1284  registerConverter( mlc, mlp, mlr );
1285 }
1286 
1287 bool Driver::registerEventConverter(const std::string& key, const dataType::DataType& type)
1288 {
1289  dataType::DataType data_type;
1290  qi::AnyValue value;
1291  try {
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: "
1296  << BOLDCYAN << key << RESETCOLOR << std::endl;
1297  return false;
1298  }
1299 
1300  if (type==dataType::None) {
1301  try {
1302  data_type = helpers::naoqi::getDataType(value);
1303  } catch (const std::exception& e) {
1304  std::cout << BOLDRED << "Could not get a valid data type to register memory converter "
1305  << BOLDCYAN << key << RESETCOLOR << std::endl
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;
1312  return false;
1313  }
1314  }
1315  else {
1316  data_type = type;
1317  }
1318 
1319  switch (data_type) {
1320  case 0:
1321  return false;
1322  break;
1323  case 1:
1324  {
1326  boost::make_shared<EventRegister<converter::MemoryFloatConverter,publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::FloatStamped> > >( key, sessionPtr_ );
1327  insertEventConverter(key, event_register);
1328  break;
1329  }
1330  case 2:
1331  {
1333  boost::make_shared<EventRegister<converter::MemoryIntConverter,publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::IntStamped> > >( key, sessionPtr_ );
1334  insertEventConverter(key, event_register);
1335  break;
1336  }
1337  case 3:
1338  {
1340  boost::make_shared<EventRegister<converter::MemoryStringConverter,publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::StringStamped> > >( key, sessionPtr_ );
1341  insertEventConverter(key, event_register);
1342  break;
1343  }
1344  case 4:
1345  {
1347  boost::make_shared<EventRegister<converter::MemoryBoolConverter,publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::BoolStamped> > >( key, sessionPtr_ );
1348  insertEventConverter(key, event_register);
1349  break;
1350  }
1351  default:
1352  {
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;
1359  return false;
1360  }
1361  }
1362 
1363  if (keep_looping) {
1364  event_map_.find(key)->second.startProcess();
1365  }
1366  if (publish_enabled_) {
1367  event_map_.find(key)->second.isPublishing(true);
1368  }
1369 
1370  return true;
1371 }
1372 
1373 std::vector<std::string> Driver::getFilesList()
1374 {
1375  std::vector<std::string> fileNames;
1376  boost::filesystem::path folderPath( boost::filesystem::current_path() );
1377  std::vector<boost::filesystem::path> files;
1378  helpers::filesystem::getFiles(folderPath, ".bag", files);
1379 
1380  for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1381  it!=files.end(); it++)
1382  {
1383  fileNames.push_back(it->string());
1384  }
1385  return fileNames;
1386 }
1387 
1389 {
1390  boost::filesystem::path folderPath( boost::filesystem::current_path() );
1391  std::vector<boost::filesystem::path> files;
1392  helpers::filesystem::getFiles(folderPath, ".bag", files);
1393 
1394  for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1395  it!=files.end(); it++)
1396  {
1397  std::remove(it->c_str());
1398  }
1399 }
1400 
1401 void Driver::removeFiles(std::vector<std::string> files)
1402 {
1403  for (std::vector<std::string>::const_iterator it=files.begin();
1404  it!=files.end(); it++)
1405  {
1406  std::remove(it->c_str());
1407  }
1408 }
1409 
1412  minidump,
1418  getMasterURI,
1419  setMasterURI,
1426  getFilesList,
1428  removeFiles,
1431  stopRecording,
1432  startLogging,
1433  stopLogging );
1434 } //naoqi
Converter concept interface.
Definition: converter.hpp:42
void publish(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
d
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...
Definition: service.hpp:59
const int kBottomCamera
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...
Definition: recorder.hpp:93
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...
Definition: publisher.hpp:77
f
qi::SessionPtr sessionPtr_
std::vector< converter::Converter > converters_
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher
#define GREEN
Definition: tools.hpp:23
bool sleep() const
#define for_each
Recorder concept interface.
Definition: recorder.hpp:46
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
Definition: subscriber.hpp:79
std::string name() const
getting the descriptive name for this converter instance
Definition: converter.hpp:59
void getFiles(const boost::filesystem::path &root, const std::string &ext, std::vector< boost::filesystem::path > &ret)
static std::string prefix
Definition: ros_env.hpp:64
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
#define BOLDRED
Definition: tools.hpp:25
void write(diagnostic_msgs::DiagnosticArray &msg)
Subscriber concept interface.
Definition: subscriber.hpp:41
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 loadBootConfig()
void registerDefaultConverter()
const int kDepthCamera
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)
#define RESETCOLOR
Definition: tools.hpp:22
std::vector< subscriber::Subscriber > subscribers_
#define HIGHGREEN
Definition: tools.hpp:24
boost::scoped_ptr< ros::NodeHandle > nhPtr_
static void setPrefix(std::string s)
Definition: ros_env.hpp:66
virtual void publish(const naoqi_bridge_msgs::StringStamped &msg)
boost::thread publisherThread_
Converter concept interface.
Definition: event.hpp:44
static void init()
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.
Definition: publisher.hpp:41
std::map< std::string, event::Event > event_map_
#define BOLDCYAN
Definition: tools.hpp:28
void registerDefaultServices()
std::map< std::string, publisher::Publisher >::const_iterator PubConstIter
float frequency() const
getting the assigned frequency of this converter instance
Definition: converter.hpp:68
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()
Definition: ros_env.hpp:100
dc
const int kTopCamera
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)
Definition: ros_env.hpp:77
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
const int kInfraredOrStereoCamera
static std::string getROSIP(std::string network_interface)
Definition: ros_env.hpp:46
boost::shared_ptr< recorder::GlobalRecorder > recorder_
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: converter.hpp:78
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
#define BOLDYELLOW
Definition: tools.hpp:27
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
static Time now()
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
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 ...
Definition: subscriber.hpp:68
std::map< std::string, event::Event >::iterator EventIter
void getFilesSize(const boost::filesystem::path &root, long &file_size)
float getBufferDuration()
float buffer_duration_
Service concept interface.
Definition: service.hpp:41
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...


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