109 #include <boost/foreach.hpp>
110 #include <boost/property_tree/json_parser.hpp>
111 #define for_each BOOST_FOREACH
122 publish_enabled_(false),
123 record_enabled_(false),
126 recorder_(
boost::make_shared<recorder::GlobalRecorder>(
prefix)),
131 std::cout <<
"Error driver prefix must not be empty" << std::endl;
132 throw new ros::Exception(
"Error driver prefix must not be empty");
142 std::cout <<
"naoqi driver is shutting down.." << std::endl;
164 std::cout <<
"load boot config from " << file_path << std::endl;
165 if (!file_path.empty())
167 boost::property_tree::read_json( file_path,
boot_config_ );
181 static std::vector<message_actions::MessageAction> actions;
213 boost::mutex::scoped_lock lock_record(
mutex_record_, boost::try_to_lock );
227 if (actions.size() >0)
264 const std::string& err =
"Log is not enabled, please enable logging before calling minidump";
265 std::cout <<
BOLDRED << err << std::endl
272 boost::filesystem::path folderPath(boost::filesystem::current_path());
276 std::cout <<
BOLDRED <<
"No more space on robot. You need to upload the presents bags and remove them to make new ones."
277 << std::endl <<
"To remove all the presents bags, you can run this command:" << std::endl
278 <<
"\t$ qicli call ROS-Driver.removeFiles" <<
RESETCOLOR << std::endl;
279 return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
292 iterator->second.isDumping(
true);
303 iterator->second.writeDump(time);
307 iterator->second.writeDump(time);
314 iterator->second.isDumping(
false);
323 const std::string& err =
"Log is not enabled, please enable logging before calling minidump";
324 std::cout <<
BOLDRED << err << std::endl
331 boost::filesystem::path folderPath(boost::filesystem::current_path());
335 std::cout <<
BOLDRED <<
"No more space on robot. You need to upload the presents bags and remove them to make new ones."
336 << std::endl <<
"To remove all the presents bags, you can run this command:" << std::endl
337 <<
"\t$ qicli call ROS-Driver.removeFiles" <<
RESETCOLOR << std::endl;
338 return "No more space on robot. You need to upload the presents bags and remove them to make new ones.";
351 iterator->second.isDumping(
true);
358 bool is_started =
false;
369 it->second.writeDump(time);
381 it_event->second.writeDump(time);
389 iterator->second.isDumping(
false);
397 std::cout <<
BOLDRED <<
"Could not find any topic in recorders" <<
RESETCOLOR << std::endl
398 <<
BOLDYELLOW <<
"To get the list of all available converter's name, please run:" <<
RESETCOLOR << std::endl
399 <<
GREEN <<
"\t$ qicli call ROS-Driver.getAvailableConverters" <<
RESETCOLOR << std::endl;
400 return "Could not find any topic in converters. To get the list of all available converter's name, please run: $ qicli call ROS-Driver.getAvailableConverters";
408 iterator->second.setBufferDuration(duration);
412 iterator->second.setBufferDuration(duration);
438 pub_map_.insert( std::map<std::string, publisher::Publisher>::value_type(conv_name, pub) );
446 rec_map_.insert( std::map<std::string, recorder::Recorder>::value_type(conv_name, rec) );
453 event_map_.insert( std::map<std::string, event::Event>::value_type(key, event) );
479 qi::AnyObject p_memory =
sessionPtr_->service(
"ALMemory").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: "
490 }
catch (
const std::exception& e) {
491 std::cout <<
BOLDRED <<
"Could not get a valid data type to register memory converter "
493 <<
BOLDRED <<
"You can enter it yourself, available types are:" << std::endl
494 <<
"\t > 0 - None" << std::endl
495 <<
"\t > 1 - Float" << std::endl
496 <<
"\t > 2 - Int" << std::endl
497 <<
"\t > 3 - String" << std::endl
498 <<
"\t > 4 - Bool" <<
RESETCOLOR << std::endl;
524 std::cout <<
BOLDRED <<
"Wrong data type. Available type are: " << std::endl
525 <<
"\t > 0 - None" << std::endl
526 <<
"\t > 1 - Float" << std::endl
527 <<
"\t > 2 - Int" << std::endl
528 <<
"\t > 3 - String" << std::endl
529 <<
"\t > 4 - Bool" <<
RESETCOLOR << std::endl;
544 bool info_enabled =
boot_config_.get(
"converters.info.enabled",
true);
545 size_t info_frequency =
boot_config_.get(
"converters.info.frequency", 1);
547 bool audio_enabled =
boot_config_.get(
"converters.audio.enabled",
true);
548 size_t audio_frequency =
boot_config_.get(
"converters.audio.frequency", 1);
550 bool logs_enabled =
boot_config_.get(
"converters.logs.enabled",
true);
551 size_t logs_frequency =
boot_config_.get(
"converters.logs.frequency", 10);
553 bool diag_enabled =
boot_config_.get(
"converters.diag.enabled",
true);
554 size_t diag_frequency =
boot_config_.get(
"converters.diag.frequency", 10);
556 bool imu_torso_enabled =
boot_config_.get(
"converters.imu_torso.enabled",
true);
557 size_t imu_torso_frequency =
boot_config_.get(
"converters.imu_torso.frequency", 10);
559 bool imu_base_enabled =
boot_config_.get(
"converters.imu_base.enabled",
true);
560 size_t imu_base_frequency =
boot_config_.get(
"converters.imu_base.frequency", 10);
562 bool camera_front_enabled =
boot_config_.get(
"converters.front_camera.enabled",
true);
563 size_t camera_front_resolution =
boot_config_.get(
"converters.front_camera.resolution", 1);
564 size_t camera_front_fps =
boot_config_.get(
"converters.front_camera.fps", 10);
565 size_t camera_front_recorder_fps =
boot_config_.get(
"converters.front_camera.recorder_fps", 5);
567 bool camera_bottom_enabled =
boot_config_.get(
"converters.bottom_camera.enabled",
true);
568 size_t camera_bottom_resolution =
boot_config_.get(
"converters.bottom_camera.resolution", 1);
569 size_t camera_bottom_fps =
boot_config_.get(
"converters.bottom_camera.fps", 10);
570 size_t camera_bottom_recorder_fps =
boot_config_.get(
"converters.bottom_camera.recorder_fps", 5);
572 size_t camera_depth_resolution;
573 bool camera_depth_enabled =
boot_config_.get(
"converters.depth_camera.enabled",
true);
574 size_t camera_depth_xtion_resolution =
boot_config_.get(
"converters.depth_camera.xtion_resolution", 1);
575 size_t camera_depth_stereo_resolution =
boot_config_.get(
"converters.depth_camera.stereo_resolution", 9);
576 size_t camera_depth_fps =
boot_config_.get(
"converters.depth_camera.fps", 10);
577 size_t camera_depth_recorder_fps =
boot_config_.get(
"converters.depth_camera.recorder_fps", 5);
579 bool camera_stereo_enabled =
boot_config_.get(
"converters.stereo_camera.enabled",
true);
580 size_t camera_stereo_resolution =
boot_config_.get(
"converters.stereo_camera.resolution", 15);
581 size_t camera_stereo_fps =
boot_config_.get(
"converters.stereo_camera.fps", 10);
582 size_t camera_stereo_recorder_fps =
boot_config_.get(
"converters.stereo_camera.recorder_fps", 5);
584 bool camera_ir_enabled =
boot_config_.get(
"converters.ir_camera.enabled",
true);
585 size_t camera_ir_resolution =
boot_config_.get(
"converters.ir_camera.resolution", 1);
586 size_t camera_ir_fps =
boot_config_.get(
"converters.ir_camera.fps", 10);
587 size_t camera_ir_recorder_fps =
boot_config_.get(
"converters.ir_camera.recorder_fps", 5);
589 bool joint_states_enabled =
boot_config_.get(
"converters.joint_states.enabled",
true);
590 size_t joint_states_frequency =
boot_config_.get(
"converters.joint_states.frequency", 50);
592 bool laser_enabled =
boot_config_.get(
"converters.laser.enabled",
true);
593 size_t laser_frequency =
boot_config_.get(
"converters.laser.frequency", 10);
594 float laser_range_min =
boot_config_.get<
float>(
"converters.laser.range_min", 0.1);
595 float laser_range_max =
boot_config_.get<
float>(
"converters.laser.range_max", 3.0);
597 bool sonar_enabled =
boot_config_.get(
"converters.sonar.enabled",
true);
598 size_t sonar_frequency =
boot_config_.get(
"converters.sonar.frequency", 10);
600 bool odom_enabled =
boot_config_.get(
"converters.odom.enabled",
true);
601 size_t odom_frequency =
boot_config_.get(
"converters.odom.frequency", 10);
603 bool bumper_enabled =
boot_config_.get(
"converters.bumper.enabled",
true);
604 bool hand_enabled =
boot_config_.get(
"converters.touch_hand.enabled",
true);
605 bool head_enabled =
boot_config_.get(
"converters.touch_head.enabled",
true);
611 camera_ir_enabled =
false;
612 camera_depth_resolution = camera_depth_stereo_resolution;
615 camera_depth_resolution = camera_depth_xtion_resolution;
661 if ( imu_torso_enabled )
675 if ( imu_base_enabled )
688 if ( camera_front_enabled )
700 if ( camera_bottom_enabled )
715 if ( camera_depth_enabled )
724 camera_depth_resolution,
734 if (this->
has_stereo && camera_stereo_enabled)
744 camera_stereo_resolution,
754 if ( camera_ir_enabled )
767 if ( joint_states_enabled )
788 lc->setLaserRanges(laser_range_min, laser_range_max);
799 std::vector<std::string> sonar_topics;
802 sonar_topics.push_back(
"sonar/front");
803 sonar_topics.push_back(
"sonar/back");
807 sonar_topics.push_back(
"sonar/left");
808 sonar_topics.push_back(
"sonar/right");
819 if ( audio_enabled ) {
825 boost::make_shared<AudioEventRegister>(
"audio", 0,
sessionPtr_);
828 event_map_.find(
"audio")->second.startProcess();
831 event_map_.find(
"audio")->second.isPublishing(
true);
834 std::cout <<
"Audio is not supported for NAOqi version 2.9 or greater, disabled." << std::endl;
839 if ( bumper_enabled )
841 std::vector<std::string> bumper_events;
842 bumper_events.push_back(
"RightBumperPressed");
843 bumper_events.push_back(
"LeftBumperPressed");
846 bumper_events.push_back(
"BackBumperPressed");
849 boost::make_shared<BumperEventRegister>(
"bumper", bumper_events, 0,
sessionPtr_ );
852 event_map_.find(
"bumper")->second.startProcess();
855 event_map_.find(
"bumper")->second.isPublishing(
true);
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_ );
872 event_map_.find(
"hand_touch")->second.startProcess();
875 event_map_.find(
"hand_touch")->second.isPublishing(
true);
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_ );
889 event_map_.find(
"head_touch")->second.startProcess();
892 event_map_.find(
"head_touch")->second.isPublishing(
true);
914 std::vector<subscriber::Subscriber>::iterator it;
916 size_t sub_index = 0;
924 std::cout <<
"registered subscriber:\t" << sub.
name() << std::endl;
929 std::cout <<
"re-initialized existing subscriber:\t" << it->name() << std::endl;
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_) );
957 std::vector<std::string> conv_list;
960 conv_list.push_back(conv.
name());
964 conv_list.push_back( iterator->first );
995 std::cout <<
"nodehandle reset " << std::endl;
1005 std::cout <<
BOLDRED <<
"going to register converters" <<
RESETCOLOR << std::endl;
1012 std::cout <<
"NOT going to re-register the converters" << std::endl;
1016 typedef std::map< std::string, publisher::Publisher > publisher_map;
1019 pub.second.reset(*
nhPtr_);
1034 typedef std::map< std::string, event::Event > event_map;
1037 event.second.resetPublisher(*
nhPtr_);
1045 std::cout <<
"going to start ROS loop" << std::endl;
1055 iterator->second.isPublishing(
true);
1064 iterator->second.isPublishing(
false);
1070 std::vector<std::string> publisher;
1076 if ( iterator->second.isSubscribed() )
1078 publisher.push_back( iterator->second.topic() );
1093 it->second.subscribe(
true);
1101 iterator->second.isRecording(
true);
1113 bool is_started =
false;
1125 it_rec->second.subscribe(
true);
1137 it_ev->second.isRecording(
true);
1144 std::cout <<
BOLDRED <<
"Could not find topic "
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;
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;
1172 it->second.subscribe(
false);
1177 iterator->second.isRecording(
false);
1198 iterator->second.startProcess();
1211 iterator->second.stopProcess();
1217 std::ifstream json_file;
1218 json_file.open(filepath.c_str(), std::ios_base::in);
1220 boost::property_tree::json_parser::read_json(json_file, pt);
1227 std::cout <<
BOLDRED <<
"The connection with the ROS master does not seem to be initialized." << std::endl
1229 <<
GREEN <<
"\t$ qicli call ROS-Driver.setMasterURI <YourROSCoreIP>" <<
RESETCOLOR << std::endl
1235 boost::property_tree::ptree pt;
1240 float frequency = 10.0f;
1242 frequency = pt.get<
float>(
"frequency");
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;
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;
1256 topic = pt.get<std::string>(
"topic");
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;
1264 std::vector<std::string> list;
1266 BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child(
"memKeys"))
1268 std::string topic = v.second.get_value<std::string>();
1269 list.push_back(topic);
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;
1279 std::cout <<
"The list of keys to add is empty. " << std::endl;
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: "
1309 }
catch (
const std::exception& e) {
1310 std::cout <<
BOLDRED <<
"Could not get a valid data type to register memory converter "
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;
1325 switch (data_type) {
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;
1373 event_map_.find(key)->second.isPublishing(
true);
1381 std::vector<std::string> fileNames;
1382 boost::filesystem::path folderPath( boost::filesystem::current_path() );
1383 std::vector<boost::filesystem::path> files;
1386 for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1387 it!=files.end(); it++)
1389 fileNames.push_back(it->string());
1396 boost::filesystem::path folderPath( boost::filesystem::current_path() );
1397 std::vector<boost::filesystem::path> files;
1400 for (std::vector<boost::filesystem::path>::const_iterator it=files.begin();
1401 it!=files.end(); it++)
1403 std::remove(it->c_str());
1409 for (std::vector<std::string>::const_iterator it=files.begin();
1410 it!=files.end(); it++)
1412 std::remove(it->c_str());
1427 getAvailableConverters,
1428 getSubscribedPublishers,
1429 addMemoryConverters,
1430 registerMemoryConverter,
1431 registerEventConverter,
1436 startRecordingConverters,