SceneModelLearner.cpp
Go to the documentation of this file.
1 
19 
21 
22  SceneModelLearner::SceneModelLearner(std::string pForegroundSceneModel, double pWorkspaceVolume, double pStaticBreakRatio, double pTogetherRatio, double pMaxAngleDeviation)
23  : mForegroundSceneModel(pForegroundSceneModel)
24  , mWorkspaceVolume(pWorkspaceVolume)
25  , mStaticBreakRatio(pStaticBreakRatio)
26  , mTogetherRatio(pTogetherRatio)
27  , mMaxAngleDeviation(pMaxAngleDeviation)
28  {
29  }
30 
32  {
33  }
34 
36  {
38  learner->initializeVisualizer(mSuperior);
39  }
40 
41 
42  void SceneModelLearner::addExample(const ISM::ObjectSetPtr pExample)
43 
44  {
45  // Add every example to background model.
47 
48  // Search for the learner that handles the example based on it's scene.
49  bool hasBeenAssigned = false;
50  BOOST_FOREACH(boost::shared_ptr<SceneLearner> learner, mSceneLearners)
51  {
52  hasBeenAssigned |= learner->isExampleForScene(pExample);
53 
54  if(hasBeenAssigned)
55  {
56  learner->addExampleToScene(pExample);
57  break;
58  }
59  }
60 
61  // If no learner was found, create a new one.
62  if(!hasBeenAssigned)
63  {
64  if(mForegroundSceneModel.compare(OCM_SCENE_MODEL) == 0)
65  {
67 
68  ROS_INFO_STREAM("Scene model learner: Created a new scene model of type '" << OCM_SCENE_MODEL << "'.");
69  } else {
70  throw std::invalid_argument("Scene model learner can not instanciate a model of the unknown type '" + mForegroundSceneModel + "'.");
71  }
72  }
73  }
74 
76  {
77  ROS_INFO("Scene model learner: Generating scene model.");
78 
79  // Background scene should learn it's parameters.
82 
83  // Each foreground scene shall learn it's parameters.
85  {
86  learner->setVolumeOfWorkspace(mWorkspaceVolume);
87  learner->setClusteringParameters(mStaticBreakRatio, mTogetherRatio, mMaxAngleDeviation);
88  learner->learn();
89  }
90 
91  // Set an equal distributed a priori probability for every scene.
92  // The number of scenes is the number of all foreground scene plus the background scene.
93  double priori = 1.0 / (mSceneLearners.size() + 1);
94  BOOST_FOREACH(boost::shared_ptr<SceneLearner> learner, mSceneLearners)
95  learner->setPriori(priori);
97  }
98 
99  void SceneModelLearner::saveSceneModelToFile(std::string pPathToFile)
100  {
101  ROS_INFO_STREAM("Scene model learner: Saving scene model to file: " << pPathToFile << ".");
102 
103  // This property tree represents the content of the XMl file.
104  boost::property_tree::ptree pt;
105 
106  // Export the background scene.
108 
109  // Export all foreground scenes.
110  BOOST_FOREACH(boost::shared_ptr<SceneLearner> learner, mSceneLearners)
111  learner->save(pt);
112 
113  // Write the property tree to file.
114  write_xml(pPathToFile, pt);
115  }
116 
117 }
static const std::string OCM_SCENE_MODEL
void addExampleToScene(const ISM::ObjectSetPtr pExample)
#define ROS_INFO(...)
#define ROS_INFO_STREAM(args)
std::vector< boost::shared_ptr< ForegroundSceneLearner > > mSceneLearners
void initializeVisualizer(boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > mSuperior)
SceneModelLearner(std::string pForegroundSceneModel, double pWorkspaceVolume, double pStaticBreakRatio, double pTogetherRatio, double pMaxAngleDeviation)
void addExample(const ISM::ObjectSetPtr pExample)


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