SceneLearningEngine.h
Go to the documentation of this file.
1 
18 #pragma once
19 
20 // Global includes
21 #include <string>
22 
23 // Package includes
24 #include <ros/ros.h>
25 #include <rosbag/view.h>
26 
27 #include <boost/shared_ptr.hpp>
28 #include <boost/date_time/gregorian/gregorian.hpp>
29 #include <boost/date_time/local_time/local_time.hpp>
30 
31 #include <visualization/psm/ProbabilisticSceneModelVisualization.h>
32 
33 
34 // Local includes
36 #include <ISM/utility/TableHelper.hpp>
37 #include <ISM/common_type/RecordedPattern.hpp>
38 
39 
41 
49  public:
50 
55 
60 
65  void readLearnerInput();
66 
73  void extractTracksFromDbFile(const std::string& dbFileName);
74 
78  void generateSceneModel();
79 
83  void saveSceneModel();
84 
88  void visualizeSceneModel();
92  void learn();
93 
94  private:
95 
104  void initializeSceneModel(double pWorkspaceVolume, double mStaticBreakRatio, double mTogetherRatio, double mMaxAngleDeviation);
105 
110 
111  /************************************
112  * ROS
113  ************************************/
114 
119 
124 
129 
130  /************************************
131  * Scene model
132  ************************************/
133 
138 
143 
147  std::string mBaseFrameId;
148 
152  double mScaleFactor;
153 
158 
162  std::string mDateTime;
163 
167  std::string mSceneModelName;
168 
172  std::string mSceneModelType;
173 
177  std::string mSceneModelDirectory;
178 
182  std::string mInputDbFilename;
183 
187  ISM::RecordedPatternPtr recordedPattern;
192 
197  };
198 }
boost::shared_ptr< ISM::TableHelper > tableHelper
boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > mVisualizer
void extractTracksFromDbFile(const std::string &dbFileName)
boost::shared_ptr< SceneModelLearner > mSceneModelLearner
void initializeSceneModel(double pWorkspaceVolume, double mStaticBreakRatio, double mTogetherRatio, double mMaxAngleDeviation)


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