SceneDescription.cpp
Go to the documentation of this file.
1 
19 
21 
23  {
24  mIdentifier.reset(new SceneIdentifier());
25  }
26 
28  {
29  // Close the file used for logging the runtime of this scene.
30  if(mRuntimeFile.is_open())
31  mRuntimeFile.close();
32  }
33 
34  void SceneDescription::load(boost::property_tree::ptree& pPt, std::string pAlgorithm)
35  {
36  // Load scene identifier.
37  mIdentifier->load(pPt);
38 
39  // Check, if there was a description specified.
40  if(mIdentifier->mDescription.size() == 0)
41  throw std::invalid_argument("Unable to procees loading. No description for scene specified.");
42 
43  // Check, if there was a scene object type specified.
44  if(mIdentifier->mType.size() == 0)
45  throw std::invalid_argument("Unable to procees loading. No description for scene '" + mIdentifier->mDescription + "' spedified.");
46 
47  // Check, if there the a priori probability is valid.
48  if(mIdentifier->mPriori < 0.0 || mIdentifier->mPriori > 1.0)
49  throw std::invalid_argument("Unable to procees loading. The a priori probability of scene '" + mIdentifier->mDescription + "' is invalid (value: " + boost::lexical_cast<std::string>(mIdentifier->mPriori) + ").");
50 
51  // Create a new scene content of the given type.
52  if(!std::strcmp(mIdentifier->mType.c_str(), "ocm")) {
53  ROS_INFO_STREAM("Loading foreground scene with type '" << mIdentifier->mType << "' and name '" << mIdentifier->mDescription << "'.");
54 
55  // Create a new ocm foreground scene content.
56  mContent.reset(new ForegroundSceneContent());
57  } else if(!std::strcmp(mIdentifier->mType.c_str(), "background")) {
58  ROS_INFO_STREAM("Loading background scene of type '" << mIdentifier->mType << "'.");
59 
60  // Create a new background scene content.
61  mContent.reset(new BackgroundSceneContent());
62  } else {
63  throw std::invalid_argument("Unable to procees loading. Can't create scene content of the unknown type '" + mIdentifier->mType + "'.");
64  }
65 
66  // Load scene content and initialize the inference algorithm.
67  mContent->initializeInferenceAlgorithms(pAlgorithm);
68  mContent->load(pPt);
69 
70  // Initialize output file for runtime evaluation results.
71  std::string runtimeLogPath;
72  ros::NodeHandle mNodeHandle("~");
73  if(mNodeHandle.getParam("runtime_log_path", runtimeLogPath))
74  {
75  mRuntimeFile.open(runtimeLogPath + "/" + mIdentifier->mDescription + ".csv");
76  mRuntimeFile << "sceneobject,runtime\n";
77  }
78  }
79 
81  {
82  // Debug message.
83  ROS_INFO_STREAM("Initializing visualizer for scene '" << mIdentifier->mDescription << "'.");
84 
85  // Create a new coordinator for primary scene object visualization.
86  mVisualizer.reset(new Visualization::ProbabilisticSceneVisualization(mIdentifier->mDescription));
87 
88  // Append it to supperior visualizer.
89  mSuperior->appendVisualizer(mVisualizer);
90 
91  // Forward the visualizer to the scene content.
92  if(mContent)
93  mContent->initializeVisualizer(mVisualizer);
94  }
95 
96  void SceneDescription::update(std::vector<ISM::Object> pEvidenceList)
97 
98  {
99  // Debug message.
100  ROS_INFO_STREAM("Evaluating scene '" << mIdentifier->mDescription << "'.");
101 
102  // Trigger the update process.
103  if(mContent)
104  mContent->update(pEvidenceList, mRuntimeFile);
105  }
106 
108  {
109  double result = 0.0;
110 
111  if(mContent)
112  result = mContent->getSceneProbability();
113 
114  // Debug message.
115  ROS_INFO_STREAM("The relative probability for scene '" << mIdentifier->mDescription << "' is '" << result << "'.");
116 
117  // Return P(D|S) * P(S)
118  mIdentifier->mLikelihood = result * mIdentifier->mPriori;
119  }
120 
122  {
124  }
125 
127  {
128  mIdentifier = pIdentifier;
129  }
130 
131 }
void load(boost::property_tree::ptree &pPt, std::string pAlgorithm)
boost::shared_ptr< SceneIdentifier > mIdentifier
void update(std::vector< ISM::Object > pEvidenceList)
boost::shared_ptr< Visualization::ProbabilisticSceneVisualization > mVisualizer
void initializeVisualizer(boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > mSuperior)
boost::shared_ptr< SceneContent > mContent
void setSceneIdentifier(boost::shared_ptr< SceneIdentifier > pIdentifier)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< SceneIdentifier > getSceneIdentifier()


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