SceneModelLearner.h
Go to the documentation of this file.
1 
18 #pragma once
19 
20 // Global includes
21 #include <vector>
22 
23 // Package includes
24 #include <ros/ros.h>
25 #include <ros/console.h>
26 
27 #include <boost/foreach.hpp>
28 #include <boost/shared_ptr.hpp>
29 
30 #include <boost/property_tree/ptree.hpp>
31 #include <boost/property_tree/xml_parser.hpp>
32 
33 #include <visualization/psm/ProbabilisticSceneModelVisualization.h>
34 
35 // Local includes
36 #include "learner/SceneLearner.h"
37 
39 
41 
43 
44 #include <ISM/common_type/ObjectSet.hpp>
46 
50  static const std::string OCM_SCENE_MODEL = "ocm";
51 
59  public:
60 
70  SceneModelLearner(std::string pForegroundSceneModel, double pWorkspaceVolume, double pStaticBreakRatio, double pTogetherRatio, double pMaxAngleDeviation);
71 
76 
83 
89  void addExample(const ISM::ObjectSetPtr pExample);
90 
94  void generateSceneModel();
95 
101  void saveSceneModelToFile(std::string pPathToFile);
102 
103  private:
104 
109 
114 
119 
124 
128  std::vector<boost::shared_ptr<ForegroundSceneLearner> > mSceneLearners;
129  };
130 }
static const std::string OCM_SCENE_MODEL
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