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

#include <KinematicChainVisualizer.h>

Inheritance diagram for Visualization::KinematicChainVisualizer:
Inheritance graph
[legend]

Public Member Functions

 KinematicChainVisualizer ()
 
void publishLink (boost::shared_ptr< ros::Publisher > pPublisher, unsigned int &pMarkerId, const Eigen::Vector3d pFrom, const Eigen::Vector3d pTo, double pQualityOfMatch)
 
void publishObjectPositionAsArrow (boost::shared_ptr< ros::Publisher > pPublisher, unsigned int &pMarkerId, const boost::shared_ptr< ISM::Pose > pPose, double pQualityOfMatch)
 
void publishObjectPositionAsPoint (boost::shared_ptr< ros::Publisher > pPublisher, unsigned int &pMarkerId, const boost::shared_ptr< ISM::Pose > pPose)
 
void publishObjectPositionAsPointWithScore (boost::shared_ptr< ros::Publisher > pPublisher, unsigned int &pMarkerId, const boost::shared_ptr< ISM::Pose > pPose, std::vector< double > pScores, double pQualityOfMatch)
 
void setBestStatus (bool pStatus)
 
 ~KinematicChainVisualizer ()
 
- Public Member Functions inherited from Visualization::AbstractExtendedVisualizer
 AbstractExtendedVisualizer ()
 
void setColors (const std_msgs::ColorRGBA &pFirstColor, const std_msgs::ColorRGBA &pSecondColor, const std_msgs::ColorRGBA &pThirdColor)
 
void setScaleFactor (const double pScaleFactor)
 
virtual ~AbstractExtendedVisualizer ()
 
- Public Member Functions inherited from Visualization::AbstractVisualizer
 AbstractVisualizer ()
 
void setFrameId (std::string pFrameId)
 
void setNamespace (std::string pNamespace)
 
virtual ~AbstractVisualizer ()
 

Private Member Functions

visualization_msgs::Marker generateArrowMessage (unsigned int &pMarkerId, const Eigen::Vector3d pFrom, const Eigen::Vector3d pTo, double pQualityOfMatch, double pScalePeak, double pScaleShaft, double pPeakLength)
 
visualization_msgs::Marker generatePerpendicularArrowMessage (unsigned int &pMarkerId, const boost::shared_ptr< ISM::Pose > pPose, double pQualityOfMatch, double pLength)
 
visualization_msgs::Marker generatePointMessage (unsigned int &pMarkerId, const Eigen::Vector3d pPosition)
 
visualization_msgs::Marker generateTermIndicatorMessage (unsigned int &pMarkerId, const boost::shared_ptr< ISM::Pose > pPose, double pOffset, double pScore)
 

Private Attributes

bool mBestStatus
 

Additional Inherited Members

- Protected Member Functions inherited from Visualization::AbstractExtendedVisualizer
const std_msgs::ColorRGBA getColor (unsigned int pNumber)
 
double getScaleFactor ()
 
- Protected Member Functions inherited from Visualization::AbstractVisualizer
std::string getFrameId ()
 
std::string getNamespace ()
 

Detailed Description

Visualizer class for the best recognition result.

Author
Joachim Gehrung
Version
See SVN

Definition at line 48 of file KinematicChainVisualizer.h.

Constructor & Destructor Documentation

Visualization::KinematicChainVisualizer::KinematicChainVisualizer ( )

Constructor.

Definition at line 22 of file KinematicChainVisualizer.cpp.

Visualization::KinematicChainVisualizer::~KinematicChainVisualizer ( )

Destructor.

Definition at line 27 of file KinematicChainVisualizer.cpp.

Member Function Documentation

visualization_msgs::Marker Visualization::KinematicChainVisualizer::generateArrowMessage ( unsigned int &  pMarkerId,
const Eigen::Vector3d  pFrom,
const Eigen::Vector3d  pTo,
double  pQualityOfMatch,
double  pScalePeak,
double  pScaleShaft,
double  pPeakLength 
)
private

Generates an arrow between two points. The color is determined by the pQualityOfMatch parameter where green is a perfect match and red no match at all.

Parameters
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pFromThe position to start the link from.
pToThe position to end the link.
pQualityOfMatchIndicator for the quality of match between the objects shall pose and is pose.
pScalePeakThe scale of the peak part of the arrow.
pScaleShaftThe scale of the shaft.
pPeakLengthThe length of the peak.

Definition at line 163 of file KinematicChainVisualizer.cpp.

visualization_msgs::Marker Visualization::KinematicChainVisualizer::generatePerpendicularArrowMessage ( unsigned int &  pMarkerId,
const boost::shared_ptr< ISM::Pose pPose,
double  pQualityOfMatch,
double  pLength 
)
private

Generates an arrow that points from top to bottom right onto the given position. The color is determined by the pQualityOfMatch parameter where green is a perfect match and red no match at all.

Parameters
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPoseThe point to point to.
pQualityOfMatchIndicator for the quality of match between the objects shall pose and is pose.
pLengthThe length of the arrow.

Definition at line 220 of file KinematicChainVisualizer.cpp.

visualization_msgs::Marker Visualization::KinematicChainVisualizer::generatePointMessage ( unsigned int &  pMarkerId,
const Eigen::Vector3d  pPosition 
)
private

Generates the visualization message that contains a point right at the given position.

Parameters
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPositionThe position of the object.
Returns
A marker array holding the visualization messages.

Definition at line 118 of file KinematicChainVisualizer.cpp.

visualization_msgs::Marker Visualization::KinematicChainVisualizer::generateTermIndicatorMessage ( unsigned int &  pMarkerId,
const boost::shared_ptr< ISM::Pose pPose,
double  pOffset,
double  pScore 
)
private

Generates a vertical chain of spheres that are colored depending on the given term scores.

Parameters
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPoseThe point to start the chain from.
pOffsetThe vertical offset to the given position.
pScoresA vector holding the scores of the single terms.
pLengthThe length of the chain.

Definition at line 245 of file KinematicChainVisualizer.cpp.

void Visualization::KinematicChainVisualizer::publishLink ( boost::shared_ptr< ros::Publisher pPublisher,
unsigned int &  pMarkerId,
const Eigen::Vector3d  pFrom,
const Eigen::Vector3d  pTo,
double  pQualityOfMatch 
)

Publishes a link between two objects. The color is determined by the pQualityOfMatch parameter where green is a perfect match and red no match at all.

Parameters
pPublisherFor publishing the visualization message.
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pFromThe position to start the link from.
pToThe position to end the link.
pQualityOfMatchIndicator for the quality of match between the objects shall pose and is pose.

Definition at line 94 of file KinematicChainVisualizer.cpp.

void Visualization::KinematicChainVisualizer::publishObjectPositionAsArrow ( boost::shared_ptr< ros::Publisher pPublisher,
unsigned int &  pMarkerId,
const boost::shared_ptr< ISM::Pose pPose,
double  pQualityOfMatch 
)

Publishes an arrow that points from top to bottom right onto the given position.

Parameters
pPublisherFor publishing the visualization message.
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPoseThe pose of the object.
pQualityOfMatchIndicator for the quality of match between the objects shall pose and is pose.

Definition at line 31 of file KinematicChainVisualizer.cpp.

void Visualization::KinematicChainVisualizer::publishObjectPositionAsPoint ( boost::shared_ptr< ros::Publisher pPublisher,
unsigned int &  pMarkerId,
const boost::shared_ptr< ISM::Pose pPose 
)

Publishes a point right at the given position.

Parameters
pPublisherFor publishing the visualization message.
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPoseThe pose of the object.

Definition at line 49 of file KinematicChainVisualizer.cpp.

void Visualization::KinematicChainVisualizer::publishObjectPositionAsPointWithScore ( boost::shared_ptr< ros::Publisher pPublisher,
unsigned int &  pMarkerId,
const boost::shared_ptr< ISM::Pose pPose,
std::vector< double >  pScores,
double  pQualityOfMatch 
)

Publishes a point right at the given position and an arrow standing for the score.

Parameters
pPublisherFor publishing the visualization message.
pMarkerIdServes as unique id for the marker. Any marker sent with the same id will overwrite the old one.
pPoseThe pose of the object.
pScoresA vector holding the scores of the single terms.
pQualityOfMatchIndicator for the quality of match between the objects shall pose and is pose.

Definition at line 66 of file KinematicChainVisualizer.cpp.

void Visualization::KinematicChainVisualizer::setBestStatus ( bool  pStatus)

Marks the scene object with the best score.

Parameters
pStatusTrue, to select the scene object as the one with the best score.

Definition at line 113 of file KinematicChainVisualizer.cpp.

Member Data Documentation

bool Visualization::KinematicChainVisualizer::mBestStatus
private

True, if the corresponding scene object is the best one.

Definition at line 185 of file KinematicChainVisualizer.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