SceneObjectDescription.cpp
Go to the documentation of this file.
1 
19 
21 
23  {
24  }
25 
27  {
28  }
29 
30  void SceneObjectDescription::load(boost::property_tree::ptree& pPt)
31  {
32  // Extract scene object name and the type of the content.
33  mPriori = pPt.get<double>("<xmlattr>.priori");
34  mType = pPt.get<std::string>("<xmlattr>.type");
35  mDescription = pPt.get<std::string>("<xmlattr>.name");
36 
37  ROS_INFO_STREAM("Loading primary scene with type '" << mType << "' and name '" << mDescription << "'.");
38 
39  // Check, if there was a description specified.
40  if(mDescription.size() == 0)
41  throw std::invalid_argument("Unable to procees loading. No description for scene object specified.");
42 
43  // Check, if there was a scene object type specified.
44  if(mType.size() == 0)
45  throw std::invalid_argument("Unable to procees loading. No description for scene object '" + mDescription + "' spedified.");
46 
47  // Check, if there the a priori probability is valid.
48  if(mPriori < 0.0 || mPriori > 1.0)
49  throw std::invalid_argument("Unable to procees loading. The a priori probability of scene object '" + mDescription + "' is invalid (value: " + boost::lexical_cast<std::string>(mPriori) + ").");
50 
51  // Create a new scene object content of the given type.
52  if(!std::strcmp(mType.c_str(), "ocm")) {
53 
54  // Create OCM based object content.
55  mContent.reset(new OcmSceneObjectContent());
56  } else {
57  // Warn the user that the specified probabilistic model doesn't exist!
58  throw std::invalid_argument("Unable to procees loading. The probabilistic model '" + mType + "' is unknown.");
59  }
60 
61  // Load scenen content.
62  mContent->load(pPt);
63  }
64 
66  {
67  // Debug message.
68  ROS_INFO_STREAM("Initializing visualizer for primary scene object '" << mDescription << "'.");
69 
70  // Create a new coordinator for seondary scene object visualization.
71  mVisualizer.reset(new Visualization::ProbabilisticPrimarySceneObjectVisualization(mDescription));
72 
73  // Append it to supperior visualizer.
74  mSuperior->appendVisualizer(mVisualizer);
75 
76  // Forward visualizer to scene object content.
77  if(mContent)
78  mContent->initializeVisualizer(mVisualizer);
79  }
80 
81  void SceneObjectDescription::update(std::vector<ISM::Object> pEvidenceList, std::ofstream& pRuntimeLogger)
82 
83  {
84  // Debug message.
85  ROS_INFO_STREAM("> Evaluating primary scene object '" << mDescription << "'.");
86 
87  // Get the start time.
88  std::chrono::high_resolution_clock::time_point start = std::chrono::high_resolution_clock::now();
89 
90  // Forward evidence to the scene object content.
91  if(mContent)
92  mContent->update(pEvidenceList);
93 
94  // Get the stop time and dump the results to file.
95  std::chrono::duration<float> diff = std::chrono::high_resolution_clock::now() - start;
96  if(pRuntimeLogger.is_open())
97  {
98  pRuntimeLogger << mDescription << "," << std::chrono::duration_cast<std::chrono::milliseconds>(diff).count() << "\n";
99  pRuntimeLogger.flush();
100  } else {
101  ROS_INFO_STREAM("Evaluating scene object '" << mDescription << "' took " << std::chrono::duration_cast<std::chrono::milliseconds>(diff).count() << " milliseconds.");
102  }
103  }
104 
106  {
107  double result = 0.0;
108 
109  if(mContent)
110  result = mContent->getSceneObjectProbability();
111 
112  return result;
113  }
114 
116  {
117  return mPriori;
118  }
119 
121  {
122  return mDescription;
123  }
124 
126  {
127  if(mContent)
128  mContent->setBestStatus(pStatus);
129  }
130 
131 }
boost::shared_ptr< Visualization::ProbabilisticPrimarySceneObjectVisualization > mVisualizer
void initializeVisualizer(boost::shared_ptr< Visualization::ProbabilisticSceneVisualization > mSuperior)
void update(std::vector< ISM::Object > pEvidenceList, std::ofstream &pRuntimeLogger)
#define ROS_INFO_STREAM(args)


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