#include <ProbabilisticPrimarySceneObjectVisualization.h>
Public Member Functions | |
void | addTermScore (double pScore) |
void | appendVisualizer (boost::shared_ptr< ProbabilisticSecondarySceneObjectVisualization > pVisualizer) |
void | drawInInferenceMode (const std::string pScene, const std_msgs::ColorRGBA &pColor, unsigned int &pMarkerId) |
void | drawInLearningMode (const std::string pScene, const std_msgs::ColorRGBA &pColor) |
void | drawInLearningTrajectoryMode (const std::string pScene) |
void | drawInTargetingMode (const std::string pScene, const std_msgs::ColorRGBA &pColor) |
std::string | getSceneObjectName () |
void | normalizeHypothesisScore (unsigned int pNumberOfSlots) |
ProbabilisticPrimarySceneObjectVisualization (std::string pName) | |
void | resetHypothesis () |
void | resetTermScores () |
void | setBestPoseCandidate (boost::shared_ptr< ISM::Pose > pPose) |
void | setBestStatus (bool pStatus) |
void | setDrawingParameters (const double pScale, const float pSigmaMultiplicator, const std::string pFrameId) |
void | setHypothesisScore (double pHypothesisScore) |
void | setLearningSamples (const std::vector< Eigen::Vector3d > &pSamples) |
void | setPose (boost::shared_ptr< ISM::Pose > pPose) |
~ProbabilisticPrimarySceneObjectVisualization () | |
Private Attributes | |
boost::shared_ptr< ISM::Pose > | mAbsolutePose |
double | mAppearanceScore |
boost::shared_ptr< ISM::Pose > | mBestCandidatePose |
double | mBestHypothesisScore |
boost::shared_ptr< ISM::Pose > | mBestPose |
std::vector< double > | mBestTermScores |
double | mExistenceScore |
ros::NodeHandle | mHandle |
boost::shared_ptr< ros::Publisher > | mPublisher |
std::vector< Eigen::Vector3d > | mSamples |
std::string | mSceneObject |
std::vector< boost::shared_ptr< ProbabilisticSecondarySceneObjectVisualization > > | mSceneObjectVisualizers |
double | mShapeScore |
std::vector< double > | mTermScores |
CoordinateFrameVisualizer | visualizerFrame |
KinematicChainVisualizer | visualizerKinematics |
SampleVisualizer | visualizerSamples |
Visualizer class for primary scenes objects.
Definition at line 58 of file ProbabilisticPrimarySceneObjectVisualization.h.
Visualization::ProbabilisticPrimarySceneObjectVisualization::ProbabilisticPrimarySceneObjectVisualization | ( | std::string | pName | ) |
Constructor.
pName | The name of this primary scene object. |
Definition at line 22 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
Visualization::ProbabilisticPrimarySceneObjectVisualization::~ProbabilisticPrimarySceneObjectVisualization | ( | ) |
Destructor.
Definition at line 30 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::addTermScore | ( | double | pScore | ) |
Adds the score of one of the terms that form the best hypothesis
pScore | The score of the appearance term. |
pShapeScore | The score of the shape term. |
pExistenceScore | The score of the existence term. |
Definition at line 243 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::appendVisualizer | ( | boost::shared_ptr< ProbabilisticSecondarySceneObjectVisualization > | pVisualizer | ) |
Appends a scene object visualizer.
pVisualizer | The scene object visualizer to append. |
Definition at line 34 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::drawInInferenceMode | ( | const std::string | pScene, |
const std_msgs::ColorRGBA & | pColor, | ||
unsigned int & | pMarkerId | ||
) |
Draws the kinematic chain for the best scoring hypothesis regarding the assignment of evidence to the slots. A chain for every primary scene object for every scene will be visualized in a separate topic. One ring color implies the primary scene object, the other the secondary scene object.
pScene | The name of the scene. Required for creating un unique frame id. |
pColor | The color indicating the scene object. |
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
Definition at line 119 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::drawInLearningMode | ( | const std::string | pScene, |
const std_msgs::ColorRGBA & | pColor | ||
) |
Draws every primary scene object in a distinct coordinate frame. One ring color implies the primary scene object, the other the secondary scene object.
pScene | The name of the scene. Required for creating un unique frame id. |
pColor | The color indicating the scene object. |
Definition at line 165 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::drawInLearningTrajectoryMode | ( | const std::string | pScene | ) |
Draws the object trajectories used for learning.
pScene | The name of the scene. Required for creating un unique frame id. |
Definition at line 202 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::drawInTargetingMode | ( | const std::string | pScene, |
const std_msgs::ColorRGBA & | pColor | ||
) |
Draws the probability distribuion indicating the position of the other scene objects. One ring color implies the primary scene object, the other the secondary scene object.
pScene | The name of the scene. Required for creating un unique frame id. |
pColor | The color indicating the scene object. |
Definition at line 78 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
std::string Visualization::ProbabilisticPrimarySceneObjectVisualization::getSceneObjectName | ( | ) |
Returns the name of the primary scene object associated with this visualizer.
Definition at line 238 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::normalizeHypothesisScore | ( | unsigned int | pNumberOfSlots | ) |
Normalizes the score for the best hypothesis.
pNumberOfSlots | The number of slots used for normalization. |
Definition at line 270 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::resetHypothesis | ( | ) |
Resets the candidates and positions.
Definition at line 275 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::resetTermScores | ( | ) |
Resets all term scores.
Definition at line 248 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setBestPoseCandidate | ( | boost::shared_ptr< ISM::Pose > | pPose | ) |
The best absolute pose of the primary object. It was determined by the best scoring hypothesis regarding the assignment of evidence to the slots.
pPose | Best absolute pose of the primary scene object. |
Definition at line 63 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setBestStatus | ( | bool | pStatus | ) |
Marks the scene object with the best score.
pStatus | True, to select the scene object as the one with the best score. |
Definition at line 281 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setDrawingParameters | ( | const double | pScale, |
const float | pSigmaMultiplicator, | ||
const std::string | pFrameId | ||
) |
Sets the parameter requried for visualizing the secondary scene object.
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 39 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setHypothesisScore | ( | double | pHypothesisScore | ) |
If the given score is better than the last best score, the last best pose is overwritten by the last pose.
pHypothesisScore | The score of the last hypothesis. |
Definition at line 253 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setLearningSamples | ( | const std::vector< Eigen::Vector3d > & | pSamples | ) |
Sets the list of samples used for learning the gaussian mixture distribution.
pSamples | The list of samples used for learning the gaussian mixture distribution. |
Definition at line 73 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
void Visualization::ProbabilisticPrimarySceneObjectVisualization::setPose | ( | boost::shared_ptr< ISM::Pose > | pPose | ) |
Sets the absolute pose of the primary object associated with this visualizer.
pPose | Absolute pose of the primary scene object. |
Definition at line 53 of file ProbabilisticPrimarySceneObjectVisualization.cpp.
|
private |
The absolute pose of the primary object associated with this visualizer.
Definition at line 225 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
The score of the single terms the best hypothesis score is made of.
Definition at line 240 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Candidate for the best absolute position of the primary object. It was determined by the best scoring hypothesis regarding the assignment of evidence to the slots.
Definition at line 250 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
The score of the best hypothesis.
Definition at line 230 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Best absolute pose of the primary object. It was determined by the best scoring hypothesis regarding the assignment of evidence to the slots.
Definition at line 245 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Definition at line 235 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Definition at line 240 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Node handle for inintializing the publisher.
Definition at line 200 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Publisher for all visualization messages generated in this class.
Definition at line 205 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
The list of samples used for learning the gaussian mixture distribution.
Definition at line 260 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
The name of this primary scene object.
Definition at line 195 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
A list of visualizers for all appended secondary scene objects.
Definition at line 255 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Definition at line 240 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
A list of the current term scores and the best term scores.
Definition at line 235 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Visualization helper for coordinate frames.
Definition at line 210 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Visualization helper for the kinematic chain.
Definition at line 215 of file ProbabilisticPrimarySceneObjectVisualization.h.
|
private |
Visualization helper for point clound.
Definition at line 220 of file ProbabilisticPrimarySceneObjectVisualization.h.