SceneModelDescription.cpp
Go to the documentation of this file.
1 
19 
21 
23  {
24  }
25 
27  {
28  }
29 
30  void SceneModelDescription::loadModelFromFile(std::string pPathToFile, std::string pAlgorithm)
31  {
32  // Check, if the file containing the model exist.
33  if(!boost::filesystem::exists(pPathToFile))
34  throw std::invalid_argument("Unable to procees loading. The model file doesn't exist!");
35 
36  // Status information for the user.
37  ROS_INFO_STREAM("Loading scene model from this location: " << pPathToFile);
38 
39  // Load model file into memory.
40  boost::property_tree::ptree pt;
41  read_xml(pPathToFile, pt);
42 
43  // Recursively load all scenes found in the XML file.
44  BOOST_FOREACH(boost::property_tree::ptree::value_type &v, pt.get_child("psm.scenes"))
45  {
46  // Create a new fore- or background scene instance.
48 
49  // Let it load its parameters...
50  scene->load(v.second, pAlgorithm);
51 
52  // ... and list it.
53  mScenes.push_back(scene);
54  }
55  }
56 
58  {
59  // Iterate over all scenes and initialize their visualizers.
61  scene->initializeVisualizer(mSuperior);
62  }
63 
65 
66  {
67  // Add the evidence found to the buffer.
68  mObjectEvidence.push(pObject);
69  }
70 
72  {
73  // Check if new evidences have been found since the last update.
75  {
76  // Integrate the evidences into what we already know.
78 
79  // Get a list of ALL evidence...
81 
82  // ... and forward it down the model.
83  BOOST_FOREACH(boost::shared_ptr<SceneDescription> scene, mScenes)
84  scene->update(mEvidenceList);
85  }
86  }
87 
88  void SceneModelDescription::getSceneListWithProbabilities(std::vector<SceneIdentifier>& pSceneList)
89  {
90  double sum = 0.0;
91 
92  pSceneList.clear();
93 
94  // Recalculate the probabilities of all scenes and collect their scene identifiers.
95  BOOST_FOREACH(boost::shared_ptr<SceneDescription> scene, mScenes)
96  {
97  // Recalculate probability.
98  scene->calculateSceneProbaility();
99 
100  // Get the scene identifier and sum it up.
101  SceneIdentifier i = *(scene->getSceneIdentifier());
102  sum += i.mLikelihood;
103 
104  // Add the identifier to the list.
105  pSceneList.push_back(i);
106  }
107 
108  // Normalize the probabilities.
109  if(sum > 0.0)
110  for(unsigned int i = 0; i < pSceneList.size(); i++)
111  pSceneList[i].mLikelihood /= sum;
112  }
113 
114 }
void initializeVisualizer(boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > mSuperior)
std::vector< boost::shared_ptr< SceneDescription > > mScenes
void integrateEvidence(const boost::shared_ptr< const ISM::Object > &pObject)
void push(const boost::shared_ptr< const ISM::Object > &pObject)
void getSceneListWithProbabilities(std::vector< SceneIdentifier > &pSceneList)
#define ROS_INFO_STREAM(args)
void loadModelFromFile(std::string pPathToFile, std::string pAlgorithm)
void getEvidences(std::vector< ISM::Object > &pEvidences)


asr_psm
Author(s): Braun Kai, Gehrung Joachim, Heizmann Heinrich, Meißner Pascal
autogenerated on Fri Nov 15 2019 03:57:54