Public Member Functions | Private Attributes | List of all members
Visualization::ProbabilisticSecondarySceneObjectVisualization Class Reference

#include <ProbabilisticSecondarySceneObjectVisualization.h>

Public Member Functions

void appendKernel (const boost::shared_ptr< Eigen::Vector3d > &pMean, const boost::shared_ptr< Eigen::Matrix3d > &pCovariance)
 
void overwriteLastBestPose ()
 
 ProbabilisticSecondarySceneObjectVisualization ()
 
 ProbabilisticSecondarySceneObjectVisualization (std::string pName)
 
void resetCertainty ()
 
void setAbsoluteLearningSamples (const std::vector< Eigen::Vector3d > &pRelativeSamples, const std::vector< Eigen::Vector3d > &pAbsoluteSamples, const std::vector< Eigen::Vector3d > &pAbsoluteParentSamples)
 
void setBestCandidatePose (boost::shared_ptr< ISM::Pose > pPose)
 
void setBestPoseCandidate (double pScore)
 
void setColors (const std_msgs::ColorRGBA &pFirstRingColor, const std_msgs::ColorRGBA &pSecondRingColor)
 
void setDetectionCertainty (double pCertainty)
 
void setDrawingParameters (const double pScale, const float pSigmaMultiplicator, const std::string pFrameId)
 
void setLastPose (boost::shared_ptr< ISM::Pose > pPose)
 
void setNamespace (std::string pNamespace)
 
void setParentPose (boost::shared_ptr< ISM::Pose > pPose)
 
void visualizeAbsoluteTrajectory (unsigned int &pMarkerId)
 
void visualizeGaussianKernels (unsigned int &pMarkerId)
 
void visualizeKinematicChain (unsigned int &pMarkerId)
 
void visualizeObjectPositionAsArrow (unsigned int &pMarkerId)
 
void visualizeRelativeTrajectory (unsigned int &pMarkerId)
 
 ~ProbabilisticSecondarySceneObjectVisualization ()
 

Private Attributes

std::vector< Eigen::Vector3d > mAbsoluteParentSamples
 
std::vector< Eigen::Vector3d > mAbsoluteSamples
 
boost::shared_ptr< ISM::PosemBestCandidatePose
 
boost::shared_ptr< ISM::PosemBestPose
 
double mBestScore
 
double mBestScoreCandidate
 
double mCertainty
 
ros::NodeHandle mHandle
 
std::vector< std::pair< Eigen::Vector3d, Eigen::Matrix3d > > mKernels
 
boost::shared_ptr< ISM::PosemLastObjectPose
 
boost::shared_ptr< ISM::PosemParentPose
 
boost::shared_ptr< ros::PublishermPublisher
 
std::vector< Eigen::Vector3d > mRelativeSamples
 
std::string mSceneObject
 
CoordinateFrameVisualizer visualizerFrame
 
GaussianKernelVisualizer visualizerKernel
 
KinematicChainVisualizer visualizerKinematics
 
SampleVisualizer visualizerSamples
 

Detailed Description

Visualizer class for secondary scenes objects.

Author
Joachim Gehrung
Version
See SVN

Definition at line 53 of file ProbabilisticSecondarySceneObjectVisualization.h.

Constructor & Destructor Documentation

Visualization::ProbabilisticSecondarySceneObjectVisualization::ProbabilisticSecondarySceneObjectVisualization ( )

Constructor.

Definition at line 22 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

Visualization::ProbabilisticSecondarySceneObjectVisualization::ProbabilisticSecondarySceneObjectVisualization ( std::string  pName)

Constructor.

Parameters
pNameThe name of this secondary scene object.

Definition at line 30 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

Visualization::ProbabilisticSecondarySceneObjectVisualization::~ProbabilisticSecondarySceneObjectVisualization ( )

Destructor.

Definition at line 39 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

Member Function Documentation

void Visualization::ProbabilisticSecondarySceneObjectVisualization::appendKernel ( const boost::shared_ptr< Eigen::Vector3d > &  pMean,
const boost::shared_ptr< Eigen::Matrix3d > &  pCovariance 
)

Appends a kernel that will be visualized in form of a covariance ellipse.

Parameters
pCovarianceA 3x3 eigen matrix representing the corvariance matrix of the gaussian kernel.
pMeanA 3d eigen vector representing the mean of the gaussian kernel.

Definition at line 151 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::overwriteLastBestPose ( )

Takes the last stored candidate for the best pose as the last best pose. This method is invoked by the primary scene object.

Definition at line 145 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::resetCertainty ( )

Resets the certainty value that describes the fitting of the associated scene object.

Definition at line 97 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setAbsoluteLearningSamples ( const std::vector< Eigen::Vector3d > &  pRelativeSamples,
const std::vector< Eigen::Vector3d > &  pAbsoluteSamples,
const std::vector< Eigen::Vector3d > &  pAbsoluteParentSamples 
)

Sets the samples used for model learning and the corresponding poses for the parent object.

Parameters
pRelativeSamplesThe list of relative poses to the parent.
pAbsoluteSamplesThe list of absolute samples used for model learning.
pAbsoluteParentSamplesThe list of corresponding poses for the parent object.

Definition at line 136 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setBestCandidatePose ( boost::shared_ptr< ISM::Pose pPose)

Sets a candidate for the absolute pose of the associated object. The primary scene object will decide based on the hypothsis score, if it is the best absolute pose.

Parameters
pPoseBest absolute pose of the primary scene object.

Definition at line 111 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setBestPoseCandidate ( double  pScore)

Sets a candidate pScore for the link between this object and its parent. The primary scene object will decide based on the hypothsis score, if it is the best score for the link.

Parameters
pScoreThe score.

Definition at line 121 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setColors ( const std_msgs::ColorRGBA &  pFirstRingColor,
const std_msgs::ColorRGBA &  pSecondRingColor 
)

Sets the colors of the two rings around the covariance ellipse.

Parameters
pFirstRingColorThe color of the first ring.
pSecondRingColorThe color of the second ring.

Definition at line 72 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setDetectionCertainty ( double  pCertainty)

Sets the certainty value that describes the fitting of the associated scene object.

Parameters
pCertaintyThe certainty betwween 0 and 1.

Definition at line 86 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setDrawingParameters ( const double  pScale,
const float  pSigmaMultiplicator,
const std::string  pFrameId 
)

Sets the parameter requried for visualizing the secondary scene object.

Parameters
pScaleFactor to multiply the kernel with.
pSigmaMultiplicatorScaling factor for the size of the visualized covariance ellipsoid.
pFrameIdThe name of the coordinate frame that should be drawn into.

Definition at line 43 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setLastPose ( boost::shared_ptr< ISM::Pose pPose)

Sets the last known pose of the associated object.

Parameters
pPoseThe last known pose.

Definition at line 102 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setNamespace ( std::string  pNamespace)

Sets the name space bases on the names of scene and scene object.

Parameters
pNamespaceThe namespace to use for visualization.

Definition at line 58 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::setParentPose ( boost::shared_ptr< ISM::Pose pPose)

Sets the absolute pose of the parent object.

Parameters
pPoseAbsolute pose of the primary scene object.

Definition at line 126 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizeAbsoluteTrajectory ( unsigned int &  pMarkerId)

Visualizes the absolute trajectory.

Parameters
pMarkerIdAn unique id for the marker. Any marker sent with the same id will overwrite the old one.

Definition at line 231 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizeGaussianKernels ( unsigned int &  pMarkerId)

Visualizes all gaussian kernels given to this class.

Parameters
pMarkerIdAn unique id for the marker. Any marker sent with the same id will overwrite the old one.

Definition at line 166 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizeKinematicChain ( unsigned int &  pMarkerId)

Visualizes the kinematic chain.

Parameters
pMarkerIdAn unique id for the marker. Any marker sent with the same id will overwrite the old one.

Definition at line 199 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizeObjectPositionAsArrow ( unsigned int &  pMarkerId)

Visualizes the position of this secondary scene object.

Parameters
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.

Definition at line 184 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

void Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizeRelativeTrajectory ( unsigned int &  pMarkerId)

Visualizes the trajectory composed of the samples used for learning in relation to the parent object.

Parameters
pMarkerIdAn unique id for the marker. Any marker sent with the same id will overwrite the old one.

Definition at line 214 of file ProbabilisticSecondarySceneObjectVisualization.cpp.

Member Data Documentation

std::vector<Eigen::Vector3d> Visualization::ProbabilisticSecondarySceneObjectVisualization::mAbsoluteParentSamples
private
std::vector<Eigen::Vector3d> Visualization::ProbabilisticSecondarySceneObjectVisualization::mAbsoluteSamples
private
boost::shared_ptr<ISM::Pose> Visualization::ProbabilisticSecondarySceneObjectVisualization::mBestCandidatePose
private

Candidate for the best absolute position of the associated object. It was determined by the best scoring hypothesis regarding the assignment of evidence to the slots.

Definition at line 263 of file ProbabilisticSecondarySceneObjectVisualization.h.

boost::shared_ptr<ISM::Pose> Visualization::ProbabilisticSecondarySceneObjectVisualization::mBestPose
private

Best absolute pose of the associated object. It was determined by the best scoring hypothesis regarding the assignment of evidence to the slots.

Definition at line 258 of file ProbabilisticSecondarySceneObjectVisualization.h.

double Visualization::ProbabilisticSecondarySceneObjectVisualization::mBestScore
private

The best score for the link to the parent.

Definition at line 243 of file ProbabilisticSecondarySceneObjectVisualization.h.

double Visualization::ProbabilisticSecondarySceneObjectVisualization::mBestScoreCandidate
private

Candidate for the best score for the link to the parent.

Definition at line 248 of file ProbabilisticSecondarySceneObjectVisualization.h.

double Visualization::ProbabilisticSecondarySceneObjectVisualization::mCertainty
private

The uncertainty describes how good the associated scene object fits into the gaussian distribution.

Definition at line 238 of file ProbabilisticSecondarySceneObjectVisualization.h.

ros::NodeHandle Visualization::ProbabilisticSecondarySceneObjectVisualization::mHandle
private

Node handle for inintializing the publisher.

Definition at line 208 of file ProbabilisticSecondarySceneObjectVisualization.h.

std::vector<std::pair<Eigen::Vector3d, Eigen::Matrix3d> > Visualization::ProbabilisticSecondarySceneObjectVisualization::mKernels
private

The kernels that will be visualized in form of covariance ellipses.

Definition at line 273 of file ProbabilisticSecondarySceneObjectVisualization.h.

boost::shared_ptr<ISM::Pose> Visualization::ProbabilisticSecondarySceneObjectVisualization::mLastObjectPose
private

The last known pose of the object associated with this visualizer.

Definition at line 253 of file ProbabilisticSecondarySceneObjectVisualization.h.

boost::shared_ptr<ISM::Pose> Visualization::ProbabilisticSecondarySceneObjectVisualization::mParentPose
private

Absolute pose of the parent object.

Definition at line 268 of file ProbabilisticSecondarySceneObjectVisualization.h.

boost::shared_ptr<ros::Publisher> Visualization::ProbabilisticSecondarySceneObjectVisualization::mPublisher
private

Publisher for all visualization messages generated in this class.

Definition at line 213 of file ProbabilisticSecondarySceneObjectVisualization.h.

std::vector<Eigen::Vector3d> Visualization::ProbabilisticSecondarySceneObjectVisualization::mRelativeSamples
private

The samples used for model learning and the corresponding poses for the parent object.

Definition at line 278 of file ProbabilisticSecondarySceneObjectVisualization.h.

std::string Visualization::ProbabilisticSecondarySceneObjectVisualization::mSceneObject
private

The name of this secondary scene object.

Definition at line 203 of file ProbabilisticSecondarySceneObjectVisualization.h.

CoordinateFrameVisualizer Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizerFrame
private

Visualization helper for coordinate frames.

Definition at line 218 of file ProbabilisticSecondarySceneObjectVisualization.h.

GaussianKernelVisualizer Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizerKernel
private

Visualization helper for gaussian kernels.

Definition at line 223 of file ProbabilisticSecondarySceneObjectVisualization.h.

KinematicChainVisualizer Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizerKinematics
private

Visualization helper for the kinematic chain.

Definition at line 228 of file ProbabilisticSecondarySceneObjectVisualization.h.

SampleVisualizer Visualization::ProbabilisticSecondarySceneObjectVisualization::visualizerSamples
private

Visualization helper for point clound.

Definition at line 233 of file ProbabilisticSecondarySceneObjectVisualization.h.


The documentation for this class was generated from the following files:


asr_psm_visualizations
Author(s): Gehrung Joachim, Meißner Pascal
autogenerated on Sat Nov 9 2019 03:49:13