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").value();
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 ) {
821  // Not supported for NAOqi 2.9
822  auto naoqi_version = helpers::driver::getNaoqiVersion(sessionPtr_);
823  if (helpers::driver::isNaoqiVersionLesser(naoqi_version, 2, 9)) {
825  boost::make_shared<AudioEventRegister>("audio", 0, sessionPtr_);
826  insertEventConverter("audio", event_register);
827  if (keep_looping) {
828  event_map_.find("audio")->second.startProcess();
829  }
830  if (publish_enabled_) {
831  event_map_.find("audio")->second.isPublishing(true);
832  }
833  } else {
834  std::cout << "Audio is not supported for NAOqi version 2.9 or greater, disabled." << std::endl;
835  }
836  }
837 
839  if ( bumper_enabled )
840  {
841  std::vector<std::string> bumper_events;
842  bumper_events.push_back("RightBumperPressed");
843  bumper_events.push_back("LeftBumperPressed");
844  if (robot_ == robot::PEPPER)
845  {
846  bumper_events.push_back("BackBumperPressed");
847  }
849  boost::make_shared<BumperEventRegister>( "bumper", bumper_events, 0, sessionPtr_ );
850  insertEventConverter("bumper", event_register);
851  if (keep_looping) {
852  event_map_.find("bumper")->second.startProcess();
853  }
854  if (publish_enabled_) {
855  event_map_.find("bumper")->second.isPublishing(true);
856  }
857  }
858 
859  if ( hand_enabled )
860  {
861  std::vector<std::string> hand_touch_events;
862  hand_touch_events.push_back("HandRightBackTouched");
863  hand_touch_events.push_back("HandRightLeftTouched");
864  hand_touch_events.push_back("HandRightRightTouched");
865  hand_touch_events.push_back("HandLeftBackTouched");
866  hand_touch_events.push_back("HandLeftLeftTouched");
867  hand_touch_events.push_back("HandLeftRightTouched");
869  boost::make_shared<HandTouchEventRegister>( "hand_touch", hand_touch_events, 0, sessionPtr_ );
870  insertEventConverter("hand_touch", event_register);
871  if (keep_looping) {
872  event_map_.find("hand_touch")->second.startProcess();
873  }
874  if (publish_enabled_) {
875  event_map_.find("hand_touch")->second.isPublishing(true);
876  }
877  }
878 
879  if ( head_enabled )
880  {
881  std::vector<std::string> head_touch_events;
882  head_touch_events.push_back("FrontTactilTouched");
883  head_touch_events.push_back("MiddleTactilTouched");
884  head_touch_events.push_back("RearTactilTouched");
886  boost::make_shared<HeadTouchEventRegister>( "head_touch", head_touch_events, 0, sessionPtr_ );
887  insertEventConverter("head_touch", event_register);
888  if (keep_looping) {
889  event_map_.find("head_touch")->second.startProcess();
890  }
891  if (publish_enabled_) {
892  event_map_.find("head_touch")->second.isPublishing(true);
893  }
894  }
895 
897  if ( odom_enabled )
898  {
899  boost::shared_ptr<publisher::BasicPublisher<nav_msgs::Odometry> > lp = boost::make_shared<publisher::BasicPublisher<nav_msgs::Odometry> >( "odom" );
900  boost::shared_ptr<recorder::BasicRecorder<nav_msgs::Odometry> > lr = boost::make_shared<recorder::BasicRecorder<nav_msgs::Odometry> >( "odom" );
901  boost::shared_ptr<converter::OdomConverter> lc = boost::make_shared<converter::OdomConverter>( "odom", odom_frequency, sessionPtr_ );
902  lc->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<nav_msgs::Odometry>::publish, lp, _1) );
903  lc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::write, lr, _1) );
904  lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::bufferize, lr, _1) );
905  registerConverter( lc, lp, lr );
906  }
907 
908 }
909 
910 
911 // public interface here
913 {
914  std::vector<subscriber::Subscriber>::iterator it;
915  it = std::find( subscribers_.begin(), subscribers_.end(), sub );
916  size_t sub_index = 0;
917 
918  // if subscriber is not found, register it!
919  if (it == subscribers_.end() )
920  {
921  sub_index = subscribers_.size();
922  //sub.reset( *nhPtr_ );
923  subscribers_.push_back( sub );
924  std::cout << "registered subscriber:\t" << sub.name() << std::endl;
925  }
926  // if found, re-init them
927  else
928  {
929  std::cout << "re-initialized existing subscriber:\t" << it->name() << std::endl;
930  }
931 }
932 
934 {
935  if (!subscribers_.empty())
936  return;
937  registerSubscriber( boost::make_shared<naoqi::subscriber::TeleopSubscriber>("teleop", "/cmd_vel", "/joint_angles", sessionPtr_) );
938  registerSubscriber( boost::make_shared<naoqi::subscriber::MovetoSubscriber>("moveto", "/move_base_simple/goal", sessionPtr_, tf2_buffer_) );
939  registerSubscriber( boost::make_shared<naoqi::subscriber::SpeechSubscriber>("speech", "/speech", sessionPtr_) );
940 }
941 
943 {
944  services_.push_back( srv );
945 }
946 
947 
949 {
950  registerService( boost::make_shared<service::RobotConfigService>("get_robot_config", "/naoqi_driver/get_robot_config", sessionPtr_) );
951  registerService( boost::make_shared<service::SetLanguageService>("set_language", "/naoqi_driver/set_language", sessionPtr_) );
952  registerService( boost::make_shared<service::GetLanguageService>("get_language", "/naoqi_driver/get_language", sessionPtr_) );
953 }
954 
955 std::vector<std::string> Driver::getAvailableConverters()
956 {
957  std::vector<std::string> conv_list;
959  {
960  conv_list.push_back(conv.name());
961  }
962  for(EventConstIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
963  {
964  conv_list.push_back( iterator->first );
965  }
966 
967  return conv_list;
968 }
969 
970 /*
971 * EXPOSED FUNCTIONS
972 */
973 
974 std::string Driver::getMasterURI() const
975 {
976  return ros_env::getMasterURI();
977 }
978 
979 void Driver::setMasterURI( const std::string& uri)
980 {
981  setMasterURINet(uri, "eth0");
982 }
983 
984 void Driver::setMasterURINet( const std::string& uri, const std::string& network_interface)
985 {
986  // To avoid two calls to this function happening at the same time
987  boost::mutex::scoped_lock lock( mutex_conv_queue_ );
988 
989  // Stopping the loop if there is any
990  //stopRosLoop();
991 
992  // Reinitializing ROS Node
993  {
994  nhPtr_.reset();
995  std::cout << "nodehandle reset " << std::endl;
996  ros_env::setMasterURI( uri, network_interface );
997  nhPtr_.reset( new ros::NodeHandle("~") );
998  }
999 
1000  if(converters_.empty())
1001  {
1002  // If there is no converters, create them
1003  // (converters only depends on Naoqi, resetting the
1004  // Ros node has no impact on them)
1005  std::cout << BOLDRED << "going to register converters" << RESETCOLOR << std::endl;
1008 // startRosLoop();
1009  }
1010  else
1011  {
1012  std::cout << "NOT going to re-register the converters" << std::endl;
1013  // If some converters are already there, then
1014  // we just need to reset the registered publisher
1015  // using the new ROS node handler.
1016  typedef std::map< std::string, publisher::Publisher > publisher_map;
1017  for_each( publisher_map::value_type &pub, pub_map_ )
1018  {
1019  pub.second.reset(*nhPtr_);
1020  }
1021 
1023  {
1024  sub.reset( *nhPtr_ );
1025  }
1026 
1028  {
1029  srv.reset( *nhPtr_ );
1030  }
1031  }
1032 
1033  if (!event_map_.empty()) {
1034  typedef std::map< std::string, event::Event > event_map;
1035  for_each( event_map::value_type &event, event_map_ )
1036  {
1037  event.second.resetPublisher(*nhPtr_);
1038  }
1039  }
1040  // Start publishing again
1041  startPublishing();
1042 
1043  if ( !keep_looping )
1044  {
1045  std::cout << "going to start ROS loop" << std::endl;
1046  startRosLoop();
1047  }
1048 }
1049 
1051 {
1052  publish_enabled_ = true;
1053  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1054  {
1055  iterator->second.isPublishing(true);
1056  }
1057 }
1058 
1060 {
1061  publish_enabled_ = false;
1062  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1063  {
1064  iterator->second.isPublishing(false);
1065  }
1066 }
1067 
1068 std::vector<std::string> Driver::getSubscribedPublishers() const
1069 {
1070  std::vector<std::string> publisher;
1071  for(PubConstIter iterator = pub_map_.begin(); iterator != pub_map_.end(); iterator++)
1072  {
1073  // iterator->first = key
1074  // iterator->second = value
1075  // Repeat if you also want to iterate through the second map.
1076  if ( iterator->second.isSubscribed() )
1077  {
1078  publisher.push_back( iterator->second.topic() );
1079  }
1080  }
1081  return publisher;
1082 }
1083 
1085 {
1086  boost::mutex::scoped_lock lock_record( mutex_record_ );
1087  recorder_->startRecord();
1089  {
1090  RecIter it = rec_map_.find(conv.name());
1091  if ( it != rec_map_.end() )
1092  {
1093  it->second.subscribe(true);
1094  std::cout << HIGHGREEN << "Topic "
1095  << BOLDCYAN << conv.name() << RESETCOLOR
1096  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1097  }
1098  }
1099  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1100  {
1101  iterator->second.isRecording(true);
1102  std::cout << HIGHGREEN << "Topic "
1103  << BOLDCYAN << iterator->first << RESETCOLOR
1104  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1105  }
1106  record_enabled_ = true;
1107 }
1108 
1109 void Driver::startRecordingConverters(const std::vector<std::string>& names)
1110 {
1111  boost::mutex::scoped_lock lock_record( mutex_record_ );
1112 
1113  bool is_started = false;
1114  for_each( const std::string& name, names)
1115  {
1116  RecIter it_rec = rec_map_.find(name);
1117  EventIter it_ev = event_map_.find(name);
1118  if ( it_rec != rec_map_.end() )
1119  {
1120  if ( !is_started )
1121  {
1122  recorder_->startRecord();
1123  is_started = true;
1124  }
1125  it_rec->second.subscribe(true);
1126  std::cout << HIGHGREEN << "Topic "
1127  << BOLDCYAN << name << RESETCOLOR
1128  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1129  }
1130  else if ( it_ev != event_map_.end() )
1131  {
1132  if ( !is_started )
1133  {
1134  recorder_->startRecord();
1135  is_started = true;
1136  }
1137  it_ev->second.isRecording(true);
1138  std::cout << HIGHGREEN << "Topic "
1139  << BOLDCYAN << name << RESETCOLOR
1140  << HIGHGREEN << " is subscribed for recording" << RESETCOLOR << std::endl;
1141  }
1142  else
1143  {
1144  std::cout << BOLDRED << "Could not find topic "
1145  << BOLDCYAN << name
1146  << BOLDRED << " in recorders" << RESETCOLOR << std::endl
1147  << BOLDYELLOW << "To get the list of all available converter's name, please run:" << RESETCOLOR << std::endl
1148  << GREEN << "\t$ qicli call ROS-Driver.getAvailableConverters" << RESETCOLOR << std::endl;
1149  }
1150  }
1151  if ( is_started )
1152  {
1153  record_enabled_ = true;
1154  }
1155  else
1156  {
1157  std::cout << BOLDRED << "Could not find any topic in recorders" << RESETCOLOR << std::endl
1158  << BOLDYELLOW << "To get the list of all available converter's name, please run:" << RESETCOLOR << std::endl
1159  << GREEN << "\t$ qicli call ROS-Driver.getAvailableConverters" << RESETCOLOR << std::endl;
1160  }
1161 }
1162 
1164 {
1165  boost::mutex::scoped_lock lock_record( mutex_record_ );
1166  record_enabled_ = false;
1168  {
1169  RecIter it = rec_map_.find(conv.name());
1170  if ( it != rec_map_.end() )
1171  {
1172  it->second.subscribe(false);
1173  }
1174  }
1175  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1176  {
1177  iterator->second.isRecording(false);
1178  }
1179  return recorder_->stopRecord(::naoqi::ros_env::getROSIP("eth0"));
1180 }
1181 
1183 {
1184  log_enabled_ = true;
1185 }
1186 
1188 {
1189  log_enabled_ = false;
1190 }
1191 
1193 {
1194  if (publisherThread_.get_id() == boost::thread::id())
1195  publisherThread_ = boost::thread( &Driver::rosLoop, this );
1196  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1197  {
1198  iterator->second.startProcess();
1199  }
1200  // Create the publishing thread if needed
1201  keep_looping = true;
1202 }
1203 
1205 {
1206  keep_looping = false;
1207  if (publisherThread_.get_id() != boost::thread::id())
1208  publisherThread_.join();
1209  for(EventIter iterator = event_map_.begin(); iterator != event_map_.end(); iterator++)
1210  {
1211  iterator->second.stopProcess();
1212  }
1213 }
1214 
1215 void Driver::parseJsonFile(std::string filepath, boost::property_tree::ptree &pt){
1216  // Open json file and parse it
1217  std::ifstream json_file;
1218  json_file.open(filepath.c_str(), std::ios_base::in);
1219 
1220  boost::property_tree::json_parser::read_json(json_file, pt);
1221  json_file.close();
1222 }
1223 
1224 void Driver::addMemoryConverters(std::string filepath){
1225  // Check if the nodeHandle pointer is already initialized
1226  if(!nhPtr_){
1227  std::cout << BOLDRED << "The connection with the ROS master does not seem to be initialized." << std::endl
1228  << BOLDYELLOW << "Please run:" << RESETCOLOR << std::endl
1229  << GREEN << "\t$ qicli call ROS-Driver.setMasterURI <YourROSCoreIP>" << RESETCOLOR << std::endl
1230  << BOLDYELLOW << "before trying to add converters" << RESETCOLOR << std::endl;
1231  return;
1232  }
1233 
1234  // Open the file filepath and parse it
1235  boost::property_tree::ptree pt;
1236  parseJsonFile(filepath, pt);
1237 
1238 
1239  // Get the frequency requested (default to 10 Hz)
1240  float frequency = 10.0f;
1241  try{
1242  frequency = pt.get<float>("frequency");
1243  }
1244  catch(const boost::property_tree::ptree_bad_data& e){
1245  std::cout << "\"frequency\" could not be interpreted as float: " << e.what() << std::endl;
1246  std::cout << "Default to 10 Hz" << std::endl;
1247  }
1248  catch(const boost::property_tree::ptree_bad_path& e){
1249  std::cout << "\"frequency\" was not found: " << e.what() << std::endl;
1250  std::cout << "Default to 10 Hz" << std::endl;
1251  }
1252 
1253  // Get the topic name requested
1254  std::string topic;
1255  try{
1256  topic = pt.get<std::string>("topic");
1257  }
1258  catch(const boost::property_tree::ptree_error& e){
1259  std::cout << "\"topic\" could not be retrieved: " << e.what() << std::endl
1260  << "Cannot add new converters" << std::endl;
1261  return;
1262  }
1263 
1264  std::vector<std::string> list;
1265  try{
1266  BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child("memKeys"))
1267  {
1268  std::string topic = v.second.get_value<std::string>();
1269  list.push_back(topic);
1270  }
1271  }
1272  catch(const boost::property_tree::ptree_error& e){
1273  std::cout << "A problem occured during the reading of the mem keys list: " << e.what() << std::endl
1274  << "Cannot add new converters" << std::endl;
1275  return;
1276  }
1277 
1278  if(list.empty()){
1279  std::cout << "The list of keys to add is empty. " << std::endl;
1280  return;
1281  }
1282 
1283  // Create converter, publisher and recorder
1284  boost::shared_ptr<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> > mlp = boost::make_shared<publisher::BasicPublisher<naoqi_bridge_msgs::MemoryList> >( topic );
1285  boost::shared_ptr<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> > mlr = boost::make_shared<recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList> >( topic );
1286  boost::shared_ptr<converter::MemoryListConverter> mlc = boost::make_shared<converter::MemoryListConverter>(list, topic, frequency, sessionPtr_ );
1288  mlc->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::write, mlr, _1) );
1289  mlc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<naoqi_bridge_msgs::MemoryList>::bufferize, mlr, _1) );
1290  registerConverter( mlc, mlp, mlr );
1291 }
1292 
1293 bool Driver::registerEventConverter(const std::string& key, const dataType::DataType& type)
1294 {
1295  dataType::DataType data_type;
1296  qi::AnyValue value;
1297  try {
1298  qi::AnyObject p_memory = sessionPtr_->service("ALMemory").value();
1299  value = p_memory.call<qi::AnyValue>("getData", key);
1300  } catch (const std::exception& e) {
1301  std::cout << BOLDRED << "Could not get data in memory for the key: "
1302  << BOLDCYAN << key << RESETCOLOR << std::endl;
1303  return false;
1304  }
1305 
1306  if (type==dataType::None) {
1307  try {
1308  data_type = helpers::naoqi::getDataType(value);
1309  } catch (const std::exception& e) {
1310  std::cout << BOLDRED << "Could not get a valid data type to register memory converter "
1311  << BOLDCYAN << key << RESETCOLOR << std::endl
1312  << BOLDRED << "You can enter it yourself, available types are:" << std::endl
1313  << "\t > 0 - None" << std::endl
1314  << "\t > 1 - Float" << std::endl
1315  << "\t > 2 - Int" << std::endl
1316  << "\t > 3 - String" << std::endl
1317  << "\t > 4 - Bool" << RESETCOLOR << std::endl;
1318  return false;
1319  }
1320  }
1321  else {
1322  data_type = type;
1323  }
1324 
1325  switch (data_type) {
1326  case 0:
1327  return false;
1328  break;
1329  case 1:
1330  {
1332  boost::make_shared<EventRegister<converter::MemoryFloatConverter,publisher::BasicPublisher<naoqi_bridge_msgs::FloatStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::FloatStamped> > >( key, sessionPtr_ );
1333  insertEventConverter(key, event_register);
1334  break;
1335  }
1336  case 2:
1337  {
1339  boost::make_shared<EventRegister<converter::MemoryIntConverter,publisher::BasicPublisher<naoqi_bridge_msgs::IntStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::IntStamped> > >( key, sessionPtr_ );
1340  insertEventConverter(key, event_register);
1341  break;
1342  }
1343  case 3:
1344  {
1346  boost::make_shared<EventRegister<converter::MemoryStringConverter,publisher::BasicPublisher<naoqi_bridge_msgs::StringStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::StringStamped> > >( key, sessionPtr_ );
1347  insertEventConverter(key, event_register);
1348  break;
1349  }
1350  case 4:
1351  {
1353  boost::make_shared<EventRegister<converter::MemoryBoolConverter,publisher::BasicPublisher<naoqi_bridge_msgs::BoolStamped>,recorder::BasicEventRecorder<naoqi_bridge_msgs::BoolStamped> > >( key, sessionPtr_ );
1354  insertEventConverter(key, event_register);
1355  break;
1356  }
1357  default:
1358  {
1359  std::cout << BOLDRED << "Wrong data type. Available type are: " << std::endl
1360  << "\t > 0 - None" << std::endl
1361  << "\t > 1 - Float" << std::endl
1362  << "\t > 2 - Int" << std::endl
1363  << "\t > 3 - String" << std::endl
1364  << "\t > 4 - Bool" << RESETCOLOR << std::endl;
1365  return false;
1366  }
1367  }
1368 
1369  if (keep_looping) {
1370  event_map_.find(key)->second.startProcess();
1371  }
1372  if (publish_enabled_) {
1373  event_map_.find(key)->second.isPublishing(true);
1374  }
1375 
1376  return true;
1377 }
1378 
1379 std::vector<std::string> Driver::getFilesList()
1380 {
1381  std::vector<std::string> fileNames;
1382  boost::filesystem::path folderPath( boost::filesystem::current_path() );
1383  std::vector<boost::filesystem::path> files;
1384  helpers::filesystem::getFiles(folderPath, ".bag", files);
1385 
1386  for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1387  it!=files.end(); it++)
1388  {
1389  fileNames.push_back(it->string());
1390  }
1391  return fileNames;
1392 }
1393 
1395 {
1396  boost::filesystem::path folderPath( boost::filesystem::current_path() );
1397  std::vector<boost::filesystem::path> files;
1398  helpers::filesystem::getFiles(folderPath, ".bag", files);
1399 
1400  for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1401  it!=files.end(); it++)
1402  {
1403  std::remove(it->c_str());
1404  }
1405 }
1406 
1407 void Driver::removeFiles(std::vector<std::string> files)
1408 {
1409  for (std::vector<std::string>::const_iterator it=files.begin();
1410  it!=files.end(); it++)
1411  {
1412  std::remove(it->c_str());
1413  }
1414 }
1415 
1417  _whoIsYourDaddy,
1418  minidump,
1419  minidumpConverters,
1420  setBufferDuration,
1421  getBufferDuration,
1422  startPublishing,
1423  stopPublishing,
1424  getMasterURI,
1425  setMasterURI,
1426  setMasterURINet,
1427  getAvailableConverters,
1428  getSubscribedPublishers,
1429  addMemoryConverters,
1430  registerMemoryConverter,
1431  registerEventConverter,
1432  getFilesList,
1433  removeAllFiles,
1434  removeFiles,
1435  startRecording,
1436  startRecordingConverters,
1437  stopRecording,
1438  startLogging,
1439  stopLogging );
1440 } //naoqi
naoqi::helpers::filesystem::getBootConfigFile
std::string & getBootConfigFile()
Definition: filesystem_helpers.hpp:99
naoqi::Driver::conv_queue_
std::priority_queue< ScheduledConverter > conv_queue_
Definition: naoqi_driver.hpp:311
naoqi::recorder::SonarRecorder::bufferize
void bufferize(const std::vector< sensor_msgs::Range > &sonar_msgs)
Definition: recorder/sonar.cpp:82
naoqi::publisher::SonarPublisher::publish
void publish(const std::vector< sensor_msgs::Range > &sonar_msgs)
Definition: publishers/sonar.cpp:34
naoqi::recorder::DiagnosticsRecorder::bufferize
void bufferize(diagnostic_msgs::DiagnosticArray &msg)
Definition: recorder/diagnostics.cpp:80
naoqi::recorder::BasicEventRecorder
Definition: basic_event.hpp:38
naoqi_helpers.hpp
naoqi::Driver::startRosLoop
void startRosLoop()
Definition: naoqi_driver.cpp:1192
naoqi::helpers::driver::getRobot
const robot::Robot & getRobot(const qi::SessionPtr &session)
Definition: driver_helpers.cpp:254
naoqi::Driver::stopRecording
std::string stopRecording()
qicli call function to stop recording all registered publisher in a ROSbag
Definition: naoqi_driver.cpp:1163
naoqi::Driver::parseJsonFile
void parseJsonFile(std::string filepath, boost::property_tree::ptree &pt)
Definition: naoqi_driver.cpp:1215
naoqi::Driver::minidump
std::string minidump(const std::string &prefix)
Write a ROSbag with the last bufferized data (10s by default)
Definition: naoqi_driver.cpp:260
naoqi::Driver::setMasterURINet
void setMasterURINet(const std::string &uri, const std::string &network_interface)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:984
naoqi::recorder::SonarRecorder::write
void write(const std::vector< sensor_msgs::Range > &sonar_msgs)
Definition: recorder/sonar.cpp:35
naoqi::Driver::stopPublishing
void stopPublishing()
qicli call function to stop/disable publishing all registered publisher
Definition: naoqi_driver.cpp:1059
bool.hpp
naoqi::Driver::event_map_
std::map< std::string, event::Event > event_map_
Definition: naoqi_driver.hpp:281
naoqi::Driver::registerMemoryConverter
bool registerMemoryConverter(const std::string &key, float frequency, const dataType::DataType &type)
qicli call function to register a converter for a given memory key
Definition: naoqi_driver.cpp:475
naoqi::converter::Converter
Converter concept interface.
Definition: converter.hpp:42
naoqi::Driver::init
void init()
Definition: naoqi_driver.cpp:151
naoqi::Driver::mutex_conv_queue_
boost::mutex mutex_conv_queue_
Definition: naoqi_driver.hpp:275
naoqi::Driver::record_enabled_
bool record_enabled_
Definition: naoqi_driver.hpp:240
AL::kBottomCamera
const int kBottomCamera
Definition: alvisiondefinitions.h:37
naoqi::Driver::registerDefaultServices
void registerDefaultServices()
Definition: naoqi_driver.cpp:948
get_language.hpp
naoqi::recorder::BasicRecorder
Definition: recorder/basic.hpp:39
boost::shared_ptr
naoqi::recorder::CameraRecorder::bufferize
void bufferize(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Definition: recorder/camera.cpp:76
naoqi::Driver::subscribers_
std::vector< subscriber::Subscriber > subscribers_
Definition: naoqi_driver.hpp:289
naoqi::converter::MemoryStringConverter
Definition: converters/memory/string.hpp:37
naoqi::helpers::filesystem::getFiles
void getFiles(const boost::filesystem::path &root, const std::string &ext, std::vector< boost::filesystem::path > &ret)
Definition: filesystem_helpers.hpp:65
camera.hpp
log.hpp
GREEN
#define GREEN
Definition: tools.hpp:23
naoqi::Driver::EventConstIter
std::map< std::string, event::Event >::const_iterator EventConstIter
Definition: naoqi_driver.hpp:286
naoqi_driver.hpp
naoqi::Driver::removeAllFiles
void removeAllFiles()
Definition: naoqi_driver.cpp:1394
naoqi::message_actions::PUBLISH
@ PUBLISH
Definition: message_actions.h:11
naoqi::helpers::naoqi::getDataType
static dataType::DataType getDataType(qi::AnyValue value)
Definition: naoqi_helpers.hpp:29
session
session
naoqi::Driver::stopLogging
void stopLogging()
Definition: naoqi_driver.cpp:1187
naoqi::Driver::EventIter
std::map< std::string, event::Event >::iterator EventIter
Definition: naoqi_driver.hpp:287
naoqi::converter::MemoryBoolConverter
Definition: converters/memory/bool.hpp:37
BOLDRED
#define BOLDRED
Definition: tools.hpp:25
ros::spinOnce
ROSCPP_DECL void spinOnce()
naoqi::Driver::ScheduledConverter
Definition: naoqi_driver.hpp:295
naoqi::ros_env::getROSIP
static std::string getROSIP(std::string network_interface)
Definition: ros_env.hpp:46
naoqi::service::Service
Service concept interface.
Definition: service.hpp:41
naoqi::Driver::setMasterURI
void setMasterURI(const std::string &uri)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:979
diagnostics.hpp
naoqi::Driver::getFilesList
std::vector< std::string > getFilesList()
Definition: naoqi_driver.cpp:1379
ros_env.hpp
moveto.hpp
ros::shutdown
ROSCPP_DECL void shutdown()
float.hpp
naoqi::Driver::robot_
const robot::Robot & robot_
Definition: naoqi_driver.hpp:237
buffer.h
naoqi::subscriber::Subscriber
Subscriber concept interface.
Definition: subscriber.hpp:41
naoqi::recorder::JointStateRecorder::write
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: recorder/joint_state.cpp:37
naoqi::Driver::log_enabled_
bool log_enabled_
Definition: naoqi_driver.hpp:241
boost
basic.hpp
naoqi::Driver::stopService
void stopService()
Definition: naoqi_driver.cpp:171
set_language.hpp
memory_list.hpp
ros::Exception
for_each
#define for_each
Definition: naoqi_driver.cpp:111
naoqi::Driver::buffer_duration_
float buffer_duration_
Definition: naoqi_driver.hpp:292
joint_state.hpp
naoqi::Driver
Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is se...
Definition: naoqi_driver.hpp:65
robot_description.hpp
naoqi::helpers::driver::getNaoqiVersion
const robot::NaoqiVersion & getNaoqiVersion(const qi::SessionPtr &session)
Function that retrieves the NAOqi version of the robot.
Definition: driver_helpers.cpp:280
naoqi::Driver::registerConverter
void registerConverter(converter::Converter &conv)
registers generall converter units they are connected via callbacks to various actions such as record...
Definition: naoqi_driver.cpp:422
recorder_helpers.hpp
naoqi::ros_env::setMasterURI
static void setMasterURI(const std::string &uri, const std::string &network_interface)
Definition: ros_env.hpp:77
driver_helpers.hpp
f
f
basic.hpp
HIGHGREEN
#define HIGHGREEN
Definition: tools.hpp:24
naoqi::Driver::recorder_
boost::shared_ptr< recorder::GlobalRecorder > recorder_
Definition: naoqi_driver.hpp:249
naoqi::publisher::BasicPublisher< naoqi_bridge_msgs::StringStamped >::publish
virtual void publish(const naoqi_bridge_msgs::StringStamped &msg)
Definition: publishers/basic.hpp:61
naoqi::Driver::startPublishing
void startPublishing()
qicli call function to start/enable publishing all registered publisher
Definition: naoqi_driver.cpp:1050
naoqi::helpers::filesystem::folderMaximumSize
static const long folderMaximumSize
Definition: filesystem_helpers.hpp:40
RESETCOLOR
#define RESETCOLOR
Definition: tools.hpp:22
naoqi
Definition: converter.hpp:29
naoqi::publisher::CameraPublisher::publish
void publish(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Definition: publishers/camera.cpp:44
naoqi::Driver::tf2_buffer_
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
Definition: naoqi_driver.hpp:316
naoqi::Driver::publish_enabled_
bool publish_enabled_
Definition: naoqi_driver.hpp:239
naoqi::Driver::registerEventConverter
bool registerEventConverter(const std::string &key, const dataType::DataType &type)
qicli call function to register a converter for a given memory event
Definition: naoqi_driver.cpp:1293
naoqi::Driver::stopRosLoop
void stopRosLoop()
Definition: naoqi_driver.cpp:1204
naoqi::converter::Converter::reset
void reset()
Definition: converter.hpp:73
naoqi::Driver::startRecordingConverters
void startRecordingConverters(const std::vector< std::string > &names)
qicli call function to start recording given topics in a ROSbag
Definition: naoqi_driver.cpp:1109
naoqi::converter::IMU::TORSO
@ TORSO
Definition: imu.hpp:39
naoqi::Driver::minidumpConverters
std::string minidumpConverters(const std::string &prefix, const std::vector< std::string > &names)
Definition: naoqi_driver.cpp:319
naoqi::Driver::registerDefaultConverter
void registerDefaultConverter()
Definition: naoqi_driver.cpp:537
naoqi::Driver::getBufferDuration
float getBufferDuration()
Definition: naoqi_driver.cpp:417
naoqi::Driver::registerPublisher
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher
Definition: naoqi_driver.cpp:431
naoqi::Driver::boot_config_
boost::property_tree::ptree boot_config_
Definition: naoqi_driver.hpp:252
naoqi::Driver::services_
std::vector< service::Service > services_
Definition: naoqi_driver.hpp:290
naoqi::Driver::addMemoryConverters
void addMemoryConverters(std::string filepath)
qicli call function to add on-the-fly some memory keys extractors
Definition: naoqi_driver.cpp:1224
naoqi::Driver::~Driver
~Driver()
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.
Definition: naoqi_driver.cpp:140
imu.hpp
camera.hpp
naoqi::recorder::Recorder
Recorder concept interface.
Definition: recorder.hpp:46
naoqi::service::Service::reset
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
naoqi::Driver::getSubscribedPublishers
std::vector< std::string > getSubscribedPublishers() const
get all subscribed publishers
Definition: naoqi_driver.cpp:1068
alvisiondefinitions.h
naoqi::dataType::None
@ None
Definition: tools.hpp:64
naoqi::converter::Converter::frequency
float frequency() const
getting the assigned frequency of this converter instance
Definition: converter.hpp:68
naoqi::converter::MemoryIntConverter
Definition: converters/memory/int.hpp:37
naoqi::Driver::getAvailableConverters
std::vector< std::string > getAvailableConverters()
get all available converters
Definition: naoqi_driver.cpp:955
naoqi::converter::MemoryFloatConverter
Definition: converters/memory/float.hpp:37
naoqi::Driver::Driver
Driver(qi::SessionPtr session, const std::string &prefix)
Constructor for naoqi driver.
Definition: naoqi_driver.cpp:118
naoqi::Driver::RecIter
std::map< std::string, recorder::Recorder >::iterator RecIter
Definition: naoqi_driver.hpp:285
naoqi::helpers::recorder::bufferDefaultDuration
static const float bufferDefaultDuration
Definition: recorder_helpers.hpp:29
AL::kInfraredOrStereoCamera
const int kInfraredOrStereoCamera
Definition: alvisiondefinitions.h:39
d
d
audio.hpp
naoqi::Driver::registerService
void registerService(service::Service srv)
registers a service
Definition: naoqi_driver.cpp:942
naoqi::recorder::DiagnosticsRecorder::write
void write(diagnostic_msgs::DiagnosticArray &msg)
Definition: recorder/diagnostics.cpp:37
tf2_ros::Buffer
naoqi::Driver::removeFiles
void removeFiles(std::vector< std::string > files)
Definition: naoqi_driver.cpp:1407
naoqi::Driver::has_stereo
bool has_stereo
Definition: naoqi_driver.hpp:243
int.hpp
naoqi::recorder::JointStateRecorder::bufferize
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: recorder/joint_state.cpp:88
laser.hpp
naoqi::helpers::driver::isDepthStereo
bool isDepthStereo(const qi::SessionPtr &session)
Definition: driver_helpers.cpp:373
naoqi::helpers::driver::isNaoqiVersionLesser
bool isNaoqiVersionLesser(const robot::NaoqiVersion &naoqi_version, const int &major, const int &minor, const int &patch, const int &build)
Function that returns true if the provided naoqi_version is (strictly) lesser than the specified one ...
Definition: driver_helpers.cpp:408
naoqi::Driver::setBufferDuration
void setBufferDuration(float duration)
Definition: naoqi_driver.cpp:404
name
name
naoqi::Driver::rec_map_
std::map< std::string, recorder::Recorder > rec_map_
Definition: naoqi_driver.hpp:280
string.hpp
naoqi::converter::IMU::BASE
@ BASE
Definition: imu.hpp:40
naoqi::Driver::sessionPtr_
qi::SessionPtr sessionPtr_
Definition: naoqi_driver.hpp:235
log.hpp
naoqi::ros_env::prefix
static std::string prefix
Definition: ros_env.hpp:64
touch.hpp
filesystem_helpers.hpp
naoqi::message_actions::RECORD
@ RECORD
Definition: message_actions.h:12
naoqi::ros_env::getMasterURI
static std::string getMasterURI()
Definition: ros_env.hpp:100
naoqi::robot::PEPPER
@ PEPPER
Definition: tools.hpp:41
ros::Time::init
static void init()
naoqi::recorder::Recorder::reset
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
BOLDCYAN
#define BOLDCYAN
Definition: tools.hpp:28
naoqi::publisher::JointStatePublisher::publish
virtual void publish(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: publishers/joint_state.cpp:33
naoqi::Driver::pub_map_
std::map< std::string, publisher::Publisher > pub_map_
Definition: naoqi_driver.hpp:279
ros::Time
basic_event.hpp
naoqi::subscriber::Subscriber::name
std::string name() const
getting the descriptive name for this subscriber instance
Definition: subscriber.hpp:79
BOLDYELLOW
#define BOLDYELLOW
Definition: tools.hpp:27
naoqi::event::Event
Converter concept interface.
Definition: event.hpp:44
naoqi::Driver::nhPtr_
boost::scoped_ptr< ros::NodeHandle > nhPtr_
Definition: naoqi_driver.hpp:273
audio.hpp
naoqi::publisher::BasicPublisher
Definition: publishers/basic.hpp:34
naoqi::Driver::publisherThread_
boost::thread publisherThread_
Definition: naoqi_driver.hpp:246
camera.hpp
message_actions.h
basic.hpp
robot_config.hpp
naoqi::Driver::RecConstIter
std::map< std::string, recorder::Recorder >::const_iterator RecConstIter
Definition: naoqi_driver.hpp:284
dc
dc
diagnostics.hpp
AL::kTopCamera
const int kTopCamera
Definition: alvisiondefinitions.h:36
naoqi::Driver::keep_looping
bool keep_looping
Definition: naoqi_driver.hpp:242
speech.hpp
AL::kDepthCamera
const int kDepthCamera
Definition: alvisiondefinitions.h:38
naoqi::converter::Converter::callAll
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: converter.hpp:78
joint_state.hpp
joint_state.hpp
naoqi::QI_REGISTER_OBJECT
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)
ros::Duration::sleep
bool sleep() const
odom.hpp
info.hpp
naoqi::Driver::loadBootConfig
void loadBootConfig()
Definition: naoqi_driver.cpp:161
naoqi::Driver::converters_
std::vector< converter::Converter > converters_
Definition: naoqi_driver.hpp:278
sonar.hpp
naoqi::Driver::registerDefaultSubscriber
void registerDefaultSubscriber()
Definition: naoqi_driver.cpp:933
teleop.hpp
sonar.hpp
info.hpp
naoqi::Driver::insertEventConverter
void insertEventConverter(const std::string &key, event::Event event)
Definition: naoqi_driver.cpp:449
naoqi::Driver::registerRecorder
void registerRecorder(const std::string &conv_name, recorder::Recorder &rec, float frequency)
prepare and register a recorder
Definition: naoqi_driver.cpp:441
naoqi::helpers::filesystem::getFilesSize
void getFilesSize(const boost::filesystem::path &root, long &file_size)
Definition: filesystem_helpers.hpp:82
naoqi::Driver::PubConstIter
std::map< std::string, publisher::Publisher >::const_iterator PubConstIter
Definition: naoqi_driver.hpp:282
ros::Duration
naoqi::publisher::Publisher
Publisher concept interface.
Definition: publisher.hpp:41
naoqi::ros_env::setPrefix
static void setPrefix(std::string s)
Definition: ros_env.hpp:66
naoqi::subscriber::Subscriber::reset
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
naoqi::Driver::startRecording
void startRecording()
qicli call function to start recording all registered converter in a ROSbag
Definition: naoqi_driver.cpp:1084
naoqi::Driver::rosLoop
void rosLoop()
Definition: naoqi_driver.cpp:179
naoqi::Driver::startLogging
void startLogging()
Definition: naoqi_driver.cpp:1182
naoqi::publisher::Publisher::reset
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
naoqi::recorder::CameraRecorder::write
void write(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Definition: recorder/camera.cpp:37
naoqi::Driver::registerSubscriber
void registerSubscriber(subscriber::Subscriber sub)
registers a subscriber
Definition: naoqi_driver.cpp:912
naoqi::dataType::DataType
DataType
Definition: tools.hpp:62
naoqi::Driver::getMasterURI
std::string getMasterURI() const
qicli call function to get current master uri
Definition: naoqi_driver.cpp:974
ros::NodeHandle
naoqi::converter::Converter::name
std::string name() const
getting the descriptive name for this converter instance
Definition: converter.hpp:59
naoqi::message_actions::LOG
@ LOG
Definition: message_actions.h:13
sonar.hpp
ros::Time::now
static Time now()
naoqi::Driver::mutex_record_
boost::mutex mutex_record_
Definition: naoqi_driver.hpp:276
touch.hpp


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06