33     mPriori = pPt.get<
double>(
"<xmlattr>.priori");
    34     mType = pPt.get<std::string>(
"<xmlattr>.type");
    37     ROS_INFO_STREAM(
"Loading primary scene with type '" << mType << 
"' and name '" << mDescription << 
"'.");
    40     if(mDescription.size() == 0)
    41       throw std::invalid_argument(
"Unable to procees loading. No description for scene object specified.");
    45       throw std::invalid_argument(
"Unable to procees loading. No description for scene object '" + mDescription + 
"' spedified.");
    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) + 
").");
    52     if(!std::strcmp(mType.c_str(), 
"ocm")) {
    58       throw std::invalid_argument(
"Unable to procees loading. The probabilistic model '" + mType + 
"' is unknown.");
    88     std::chrono::high_resolution_clock::time_point start = std::chrono::high_resolution_clock::now();
    95     std::chrono::duration<float> diff = std::chrono::high_resolution_clock::now() - start;
    96     if(pRuntimeLogger.is_open())
    98       pRuntimeLogger << 
mDescription << 
"," << std::chrono::duration_cast<std::chrono::milliseconds>(diff).count() << 
"\n";
    99       pRuntimeLogger.flush();
   101       ROS_INFO_STREAM(
"Evaluating scene object '" << 
mDescription << 
"' took " << std::chrono::duration_cast<std::chrono::milliseconds>(diff).count() << 
" milliseconds.");
   110       result = 
mContent->getSceneObjectProbability();
 double getSceneObjectProbability()
~SceneObjectDescription()
void setBestStatus(bool pStatus)
boost::shared_ptr< Visualization::ProbabilisticPrimarySceneObjectVisualization > mVisualizer
double getSceneObjectPriori()
void initializeVisualizer(boost::shared_ptr< Visualization::ProbabilisticSceneVisualization > mSuperior)
void load(boost::property_tree::ptree &pPt)
std::string getDescription()
void update(std::vector< ISM::Object > pEvidenceList, std::ofstream &pRuntimeLogger)
#define ROS_INFO_STREAM(args)
boost::shared_ptr< SceneObjectContent > mContent