#include <SceneInferenceEngine.h>
Public Member Functions | |
void | executeInStackMode () |
SceneModelDescription | getModel () |
void | newObservationCallback (const boost::shared_ptr< asr_msgs::AsrObject > &pObject) |
SceneInferenceEngine () | |
void | update () |
~SceneInferenceEngine () | |
Private Member Functions | |
boost::shared_ptr< ISM::Object > | AsrObjectToISMObject (boost::shared_ptr< asr_msgs::AsrObject > pObject) |
void | initializeVisualizationChain (const double pScale, const float pSigmaMultiplicator, const std::string pFrameId) |
boost::shared_ptr< asr_msgs::AsrObject > | ISMObjectToAsrObject (boost::shared_ptr< ISM::Object > pObject) |
void | loadSceneModel (const std::string pSceneModelFileName, const std::string pInferenceAlgorithm) |
Private Attributes | |
std::queue< boost::shared_ptr< asr_msgs::AsrObject > > | mEvidenceBuffer |
SceneModelDescription | mModel |
ros::NodeHandle | mNodeHandle |
ros::Subscriber | mObjectListener |
ObjectTransformation | mObjectTransform |
ros::Subscriber | mSceneGraphListener |
bool | mTargetingHelp |
Visualization::GnuplotVisualization | mVisGnuplot |
boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > | mVisualizer |
bool | showPlot |
Probabilistic scene inference engine in form of a ROS node. This class is basically a ROS wrapper for the inference model. Engine parameters are loaded via node handle, the model is loaded from file.
Definition at line 46 of file SceneInferenceEngine.h.
ProbabilisticSceneRecognition::SceneInferenceEngine::SceneInferenceEngine | ( | ) |
Constructor.
Definition at line 22 of file SceneInferenceEngine.cpp.
ProbabilisticSceneRecognition::SceneInferenceEngine::~SceneInferenceEngine | ( | ) |
Destructor.
Definition at line 96 of file SceneInferenceEngine.cpp.
|
private |
Converts an AsrObject to ISMObject
pObject | the Object to convert |
Definition at line 328 of file SceneInferenceEngine.cpp.
void ProbabilisticSceneRecognition::SceneInferenceEngine::executeInStackMode | ( | ) |
Runs a single update and then terminates.
Definition at line 180 of file SceneInferenceEngine.cpp.
|
inline |
Returns the model. The model is responsible for loading the scene model from file, collect and manage the evidence and do the inference.
Definition at line 80 of file SceneInferenceEngine.h.
|
private |
Initializes the chain responsible for visualization.
pScale | Factor to multiply the kernel with. |
pSigmaMultiplicator | Scaling factor for the size of the visualized covariance ellipsoid. |
pFrameId | The name of the coordinate frame that should be drawn into. |
Definition at line 257 of file SceneInferenceEngine.cpp.
|
private |
Converts an ISMObject to an AsrObject
pObject | the Object to convert |
Definition at line 300 of file SceneInferenceEngine.cpp.
|
private |
Loads the probabilistic scene model from XMl file.
pSceneModelFileName | The name of the XMl file containing the scene model that should we used. |
pInferenceAlgorithm | The name of the inference algorithm. |
Definition at line 248 of file SceneInferenceEngine.cpp.
void ProbabilisticSceneRecognition::SceneInferenceEngine::newObservationCallback | ( | const boost::shared_ptr< asr_msgs::AsrObject > & | pObject | ) |
Collects evidences in form of AsrObject and forwards them to the inference model.
pObject | An observation result for a potential scene element coming from an arbitrary sensor data processing system. |
Definition at line 293 of file SceneInferenceEngine.cpp.
void ProbabilisticSceneRecognition::SceneInferenceEngine::update | ( | ) |
Updates the inference engine.
Definition at line 100 of file SceneInferenceEngine.cpp.
|
private |
A buffer for storing evidences.
Definition at line 145 of file SceneInferenceEngine.h.
|
private |
The model is responsible for loading the scene model from file, collect and manage the evidence and do the inference.
Definition at line 155 of file SceneInferenceEngine.h.
|
private |
Interface to private ros node namespace.
Definition at line 130 of file SceneInferenceEngine.h.
|
private |
A callback handler listening to objects found by an object detection system.
Definition at line 135 of file SceneInferenceEngine.h.
|
private |
A transformer for objects into the target coordinate frame.
Definition at line 150 of file SceneInferenceEngine.h.
|
private |
A callback handler listening to preprocessed observations that describe the objects in a scene over time
Definition at line 140 of file SceneInferenceEngine.h.
|
private |
Set true to overwrite the visualization of results and plot the target distributions instead.
Definition at line 125 of file SceneInferenceEngine.h.
|
private |
Gnuplot visualizer for drawing bar diagrams.
Definition at line 160 of file SceneInferenceEngine.h.
|
private |
Class for coordinating the scene visualizers.
Definition at line 165 of file SceneInferenceEngine.h.
|
private |
True to show the plot of the scene probabilities.
Definition at line 120 of file SceneInferenceEngine.h.