27 #include <asr_msgs/AsrObject.h>    28 #include <geometry_msgs/Pose.h>    29 #include <ISM/recognizer/Recognizer.hpp>    30 #include <ISM/utility/TableHelper.hpp>    31 #include <ISM/utility/GeometryHelper.hpp>    32 #include <ISM/common_type/Pose.hpp>    33 #include <tf/transform_datatypes.h>    34 #include <tf/transform_listener.h>    35 #include <visualization_msgs/MarkerArray.h>    56     object_constellation_folder_path_(
""),
    57     object_constellation_file_counter_(0),
    58     last_object_set_size_(0),
    59     results_already_shared_(results_already_shared),
    60     is_visualization_active_(true),
    61     shared_recognition_results_ptr_(shared_recognition_results_ptr)
    69     if(database_filename_.empty()){
    70         ROS_FATAL(
"DB Filename empty. Shutting down node!");
   100     table_helper_ = TableHelperPtr(
new TableHelper(database_filename_));
   101     recognizer_ = RecognizerPtr(
new Recognizer(database_filename_, bin_size_, max_projection_angle_deviation_, 
false, rater_type_));
   104     ROS_INFO(
"SceneRecognition: Initialized recognizer from ism_lib.");
   112     ROS_INFO(
"SceneRecognition: Initialized ism visualizations.");
   119     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Building pattern_object_map_ from database.");
   120     for(
string& pattern_name : 
table_helper_->getModelPatternNames())
   122         set<pair<string, string> > object_type_and_id_in_pattern =
   123                 table_helper_->getObjectTypesAndIdsBelongingToPattern(pattern_name);
   124         set<pair<string, string> > object_types_and_ids_non_sub;
   125         for (pair<string, string> 
object : object_type_and_id_in_pattern)
   128             if(
object.first.find(
"_sub") != string::npos)
   130             object_types_and_ids_non_sub.insert(make_pair(
object.first,
object.second));
   132         unsigned int last_index = pattern_name.find(
"_sub");
   133         if (last_index != string::npos)
   136             string pattern_name_without_sub = pattern_name.substr(0, last_index);
   137             ROS_DEBUG_STREAM_NAMED(
"SceneRecognition", 
"Renamed scene " << pattern_name << 
" to " << pattern_name_without_sub << 
".");
   138             pattern_name = pattern_name_without_sub;
   140         map<string, set<pair<string, string> > >::iterator it = 
pattern_object_map_.find(pattern_name);
   143             set<pair<string, string> > old_set = it->second;
   144             old_set.insert(object_types_and_ids_non_sub.begin(), object_types_and_ids_non_sub.end());
   145             it->second = old_set;
   149             pattern_object_map_.insert(pair<
string, 
set<pair<string, string> > >(pattern_name, object_types_and_ids_non_sub));
   153             ROS_DEBUG_STREAM_NAMED(
"SceneRecognition", 
"Map element for scene " << pattern_name << 
" contains object [" << obj.first << 
", " << obj.second << 
"].");
   157     vector<string> pattern_names = 
table_helper_->getModelPatternNames();
   159     for (
string pattern_name : pattern_names)
   161         if (pattern_name.find(
"_sub") == string::npos)
   169                             ObjectSetPtr temp_set_ptr, vector<ObjectSetPtr>& object_sets, 
bool measured_value_only) {
   172     if(object_it == end_it){
   173         object_sets.push_back(ObjectSetPtr( 
new ObjectSet(*temp_set_ptr)));
   178     unsigned int used_samples_count = measured_value_only ? 1 : object_it->sampledPoses.size();
   181     for (
unsigned int i = 0; i < used_samples_count; i++) {
   183       geometry_msgs::Pose sample_pose = object_it->sampledPoses.at(i).pose;
   184       double sampled_position_x = sample_pose.position.x;
   185       double sampled_position_y = sample_pose.position.y;
   186       double sampled_position_z = sample_pose.position.z;
   188       double sampled_quaternion_w = sample_pose.orientation.w;
   189       double sampled_quaternion_x = sample_pose.orientation.x;
   190       double sampled_quaternion_y = sample_pose.orientation.y;
   191       double sampled_quaternion_z = sample_pose.orientation.z;
   193       QuaternionPtr ism_quaternion_ptr = QuaternionPtr(
new Quaternion(sampled_quaternion_w,
   194                                                                       sampled_quaternion_x,
   195                                                                       sampled_quaternion_y,
   196                                                                       sampled_quaternion_z));
   197       QuaternionPtr ism_quaternion_normalized_ptr = GeometryHelper::normalize(ism_quaternion_ptr);
   199       ObjectPtr new_object(
new Object(object_it->type,
   201                                                new Point(sampled_position_x,
   204                                                ism_quaternion_normalized_ptr),
   205                       object_it->identifier,
   206                       boost::filesystem::path(object_it->meshResourcePath).replace_extension(
".dae").string()));
   208       temp_set_ptr->objects.push_back(new_object);
   212       temp_set_ptr->objects.pop_back();
   219     ROS_INFO(
"\n==================================================\n");
   220     ROS_INFO(
"Callback SceneRecognition::processFindScenesServiceCall() is called.");
   222     if (request.objects.empty())
   224         ROS_INFO(
"No objects passed to scene detection callback.");
   225         response.result_size.data = 0;
   226         response.output = 
"";
   228         ROS_INFO(
"\n==================================================\n");
   232     for (asr_msgs::AsrObject pbd_object : request.objects)
   234         ROS_ASSERT_MSG(!pbd_object.sampledPoses.empty(),
"Object estimate with no samples not allowed.");
   243     vector<ObjectSetPtr> object_sets;
   247     unsigned int number_of_combinations = 1;
   249     for (asr_msgs::AsrObject asr_object : request.objects)
   251     number_of_combinations *= asr_object.sampledPoses.size();
   260     ROS_INFO_STREAM(
"Number of object set combinations: " << object_sets.size());
   265         ROS_ASSERT_MSG(number_of_combinations == object_sets.size(), 
"Error in recursive object set generation, expect: %u actual: %zu", number_of_combinations, object_sets.size());
   268             asr_world_model::VisualizeSampledPoses srv;
   269             for (asr_msgs::AsrObject pbd_object : request.objects)
   271                 srv.request.object_type = pbd_object.type;
   272                 srv.request.object_id = pbd_object.identifier;
   278             ROS_WARN(
"visualization server from world model does not exists -> sampled poses will not be visualized");
   282         ROS_ASSERT_MSG(1 == object_sets.size(), 
"Error in recursive object set generation, expect: %u actual: %zu", 1, object_sets.size());
   290     std::vector<ISM::RecognitionResultPtr> recognition_results;
   293     for(vector<ObjectSetPtr>::iterator set_it = object_sets.begin(); set_it != object_sets.end(); set_it++) {
   299         converter->normalizeRotationInvariantObjects((*set_it));
   302         vector<RecognitionResultPtr> resultsForCombination = 
recognizer_->recognizePattern((*set_it), 0, -1);
   304         recognition_results.insert(recognition_results.end(), resultsForCombination.begin(), resultsForCombination.end());
   311     if (recognition_results.empty())
   313         ROS_INFO(
"Not any scene could be recognized by ism in input objects.");
   314         response.result_size.data = 0;
   315         response.output = 
"Not any scene could be recognized by ism in input objects.";
   317         ROS_INFO(
"\n==================================================\n");
   322     output << 
"Summary of results from SceneRecognition::processFindScenesServiceCall() in rp_ism_node." << endl;
   323     output << 
"These are the best recognition results, returned per patternName:";
   327     stable_sort(recognition_results.begin(), recognition_results.end(), 
compareConfidence);
   337         ROS_INFO(
"New objects detected since last scene recognition call.");
   338         ROS_INFO(
"Flushing shared memory with recognition results and inserting new results.");
   359             const string current_pattern_name = recognition_result_ptr->patternName;
   360             if (remaining_pattern_names_counter.find(current_pattern_name) != remaining_pattern_names_counter.end())
   364             remaining_pattern_names_counter.erase(current_pattern_name);
   372             ROS_DEBUG_NAMED(
"SceneRecognition", 
"Flushed visualization for scene recognition.");
   383     std_msgs::UInt8 result_size;
   384     result_size.data = recognition_results.size();
   385     response.result_size = result_size;
   389     response.output = output.str();
   391     ROS_INFO(
"\n==================================================\n");
   397     set<string> complete_pattern_names;
   398     vector<asr_world_model::CompletePattern> completePatternsToPush;
   400     ROS_INFO_STREAM(
"These are all sorted " << recognition_results.size() << 
" recognition results from the current recognition call:");
   402     for(RecognitionResultPtr& recognition_result_ptr : recognition_results)
   408             complete_pattern_names.insert(recognition_result_ptr->patternName);
   409             vector<asr_world_model::CompletePattern>::iterator it = find_if(completePatternsToPush.begin(), completePatternsToPush.end(), [&recognition_result_ptr]
   410                                                                         (
const asr_world_model::CompletePattern& r) { 
return r.patternName == recognition_result_ptr->patternName; } );
   411             if (it == completePatternsToPush.end()) {
   412                 asr_world_model::CompletePattern completePattern;
   413                 completePattern.patternName = recognition_result_ptr->patternName;
   414                 completePattern.confidence = recognition_result_ptr->confidence;
   415                 completePatternsToPush.push_back(completePattern);
   417                 it->confidence = max(it->confidence, static_cast<float>(recognition_result_ptr->confidence));
   422     asr_world_model::PushCompletePatterns push_complete_patterns;
   423     for (
const asr_world_model::CompletePattern &pattern : completePatternsToPush) {
   424         push_complete_patterns.request.completePatterns.push_back(pattern);
   428     for(
string pattern_name : complete_pattern_names)
   429         ROS_INFO_STREAM(
"Found all objects in scene " << pattern_name << 
", hence no pose prediction for it.");
   432     for(RecognitionResultPtr& recognition_result_ptr : recognition_results)
   435         if (complete_pattern_names.find(recognition_result_ptr->patternName) == complete_pattern_names.end())
   449         const string current_pattern_name = recognition_result_ptr->patternName;
   450         if (remaining_pattern_names.find(current_pattern_name) != remaining_pattern_names.end())
   452             output << endl << recognition_result_ptr << endl;
   460             remaining_pattern_names.erase(current_pattern_name);
   463         if (remaining_pattern_names.size() == 0)
   472     ROS_INFO(
"Now DELETING all NEW RECOGNITION RESULTS, already used for pose prediction.");
   475     int number_of_erased_incomplete_recognition_results = 0;
   485             ++number_of_erased_incomplete_recognition_results;
   488     ROS_DEBUG_STREAM_NAMED(
"SceneRecognition", 
"Number of deleted results: " << number_of_erased_incomplete_recognition_results);
   495     if (boost::filesystem::exists(request.log_dir_path))
   505                                                              Empty::Response &response)
   507     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Callback SceneRecognition::processToggleVisualizationServiceCall() is called.");
   516     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Callback SceneRecognition::processResetServiceCall() is called.");
   519     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Resetting shared mem with recognition results.");
   521     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Flushing buffer of results, already present in shared mem.");
   523     ROS_DEBUG_NAMED(
"SceneRecognition", 
"Setting configuration file counter back to 0");
   535     if (objects.size() > 0)
   537         std::ofstream myfile;
   538         string filePath = 
object_constellation_folder_path_ + 
"/" + 
"recognition_" + to_string(scene_recog_count) + 
"_constellation_" + to_string(constellation_count) + 
".xml";
   539         myfile.open(filePath);
   540         myfile << 
"<Objects>";
   542         for (
unsigned int i = 0; i < objects.size(); ++i)
   544             ObjectPtr 
object = objects[i];
   545             PosePtr pose = 
object->pose;
   547                    << 
"type=\"" << 
object->type
   548                    << 
"\" id=\"" << 
object->observedId
   549                    << 
"\" mesh=\"" << 
object->ressourcePath.string()
   550                    << 
"\" angles=\"quaternion\">"   551                    << pose->point->eigen.x()
   552                    << 
"," << pose->point->eigen.y()
   553                    << 
"," << pose->point->eigen.z()
   554                    << 
"," << pose->quat->eigen.w()
   555                    << 
"," << pose->quat->eigen.x()
   556                    << 
"," << pose->quat->eigen.y()
   557                    << 
"," << pose->quat->eigen.z()
   561         myfile << 
"</Objects>";
   568     vector<ObjectPtr> ret_objects;
   569     for(ObjectPtr obj : result->recognizedSet->objects)
   571         if( obj->type.find( result->patternName ) == string::npos)
   573             ret_objects.push_back(obj);
   577     vector<ObjectPtr> temp_objects;
   578     for (RecognitionResultPtr sub_result_ptr : result->subPatterns)
   581         ret_objects.insert( ret_objects.end(), temp_objects.begin(), temp_objects.end());
   587     return (i->confidence < j->confidence);
   592     unsigned int counter = 0;
   593     for (pair<string, string> el_a : set_a)
   595         for (pair<string, string> el_b : set_b)
   597             if(!el_a.first.compare(el_b.first) && !el_a.second.compare(el_b.second))
   601     return counter == set_a.size();
 std::string database_filename_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::string object_constellation_folder_path_
void constructPatternObjectMapping()
std::vector< ISM::RecognitionResultPtr > & results_already_shared_
ros::Publisher visualization_publisher_
std::set< std::pair< std::string, std::string > > object_types_and_ids_set_
ISM::TableHelperPtr table_helper_
#define ROS_DEBUG_STREAM_NAMED(name, args)
IH::ObjectConverterPtr converter
int enable_rotation_mode_
boost::shared_ptr< ObjectConverter > ObjectConverterPtr
std::vector< ISM::ObjectPtr > extractRealObjects(ISM::RecognitionResultPtr result_ptr)
std::string rotation_frame_
bool call(MReq &req, MRes &res)
std::string getName(void *handle)
unsigned int last_object_set_size_
bool is_visualization_active_
int object_constellation_file_counter_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool processFindScenesServiceCall(asr_recognizer_prediction_ism::FindScenes::Request &request, asr_recognizer_prediction_ism::FindScenes::Response &response)
processFindScenesServiceCall Receives service call with detected AsrObjects. 
std::vector< ISM::RecognitionResultPtr > results_for_visualization_
SharedRecognitionResultsManagerPtr shared_recognition_results_ptr_
void sortBestRRperScene(std::stringstream &output)
std::vector< ISM::RecognitionResultPtr > incomplete_recognition_results_
static bool isCompleteSubset(std::set< std::pair< std::string, std::string > > set_a, std::set< std::pair< std::string, std::string > > set_b)
#define ROS_DEBUG_NAMED(name,...)
std::map< std::string, std::set< std::pair< std::string, std::string > > > pattern_object_map_
std::set< std::string > unique_pattern_names_
ros::ServiceClient viz_samples_client_
bool setLogFilePathServiceCall(asr_recognizer_prediction_ism::SetLogDir::Request &request, asr_recognizer_prediction_ism::SetLogDir::Response &response)
processSetLogDirServiceCall Receives service call where to write object constellations, used for scene recognition. 
#define ROS_ASSERT_MSG(cond,...)
std::string viz_samples_client_name_
ros::ServiceServer toggle_visualization_server_
const std::string & getNamespace() const 
void getParam(std::string param_name, T *variable, T default_value)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void filterIncompleteRR(std::vector< ISM::RecognitionResultPtr > &recognition_results)
ros::ServiceServer set_log_dir_server_
void writeObjectConstellationToXML(std::vector< ISM::ObjectPtr > &objects, int sceneRecogCount, int constellation_count)
bool processResetServiceCall(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
processResetServiceCall Clears the old recognition results. 
std::string push_complete_patterns_name_
void createObjectSetsFromPoseSamples(std::vector< asr_msgs::AsrObject >::iterator object_it, std::vector< asr_msgs::AsrObject >::iterator end_it, ISM::ObjectSetPtr temp_set_ptr, std::vector< ISM::ObjectSetPtr > &object_sets, bool measured_value_only)
ros::NodeHandle node_handle_
ros::ServiceClient push_complete_patterns_server_
VIZ::ObjectModelVisualizerRVIZ * object_model_visualizer_
#define ROS_INFO_STREAM(args)
std::string rotation_object_type_
std::string rotation_object_id_
std::string scene_markers_publisher_name_
static bool compareConfidence(ISM::RecognitionResultPtr i, ISM::RecognitionResultPtr j)
bool processToggleVisualizationServiceCall(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
processToggleVisualizationServiceCall Toggle the visualization via service call. 
#define ROS_WARN_COND(cond,...)
#define ROS_INFO_COND(cond,...)
ros::ServiceServer reset_server_
ISM::RecognizerPtr recognizer_
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
VIZ::ISMResultVisualizerRVIZPtr res_visualizer_
double max_projection_angle_deviation_
ros::ServiceServer find_scenes_server_
unsigned int object_set_max_count_