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