#include <KinematicChainVisualizer.h>
|
| 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 () |
|
| 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 () |
|
| AbstractVisualizer () |
|
void | setFrameId (std::string pFrameId) |
|
void | setNamespace (std::string pNamespace) |
|
virtual | ~AbstractVisualizer () |
|
|
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) |
|
Visualizer class for the best recognition result.
- Author
- Joachim Gehrung
- Version
- See SVN
Definition at line 48 of file KinematicChainVisualizer.h.
Visualization::KinematicChainVisualizer::KinematicChainVisualizer |
( |
| ) |
|
Visualization::KinematicChainVisualizer::~KinematicChainVisualizer |
( |
| ) |
|
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
-
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pFrom | The position to start the link from. |
pTo | The position to end the link. |
pQualityOfMatch | Indicator for the quality of match between the objects shall pose and is pose. |
pScalePeak | The scale of the peak part of the arrow. |
pScaleShaft | The scale of the shaft. |
pPeakLength | The 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
-
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPose | The point to point to. |
pQualityOfMatch | Indicator for the quality of match between the objects shall pose and is pose. |
pLength | The 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
-
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPosition | The 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
-
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPose | The point to start the chain from. |
pOffset | The vertical offset to the given position. |
pScores | A vector holding the scores of the single terms. |
pLength | The 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
-
pPublisher | For publishing the visualization message. |
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pFrom | The position to start the link from. |
pTo | The position to end the link. |
pQualityOfMatch | Indicator for the quality of match between the objects shall pose and is pose. |
Definition at line 94 of file KinematicChainVisualizer.cpp.
Publishes an arrow that points from top to bottom right onto the given position.
- Parameters
-
pPublisher | For publishing the visualization message. |
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPose | The pose of the object. |
pQualityOfMatch | Indicator for the quality of match between the objects shall pose and is pose. |
Definition at line 31 of file KinematicChainVisualizer.cpp.
Publishes a point right at the given position.
- Parameters
-
pPublisher | For publishing the visualization message. |
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPose | The pose of the object. |
Definition at line 49 of file KinematicChainVisualizer.cpp.
Publishes a point right at the given position and an arrow standing for the score.
- Parameters
-
pPublisher | For publishing the visualization message. |
pMarkerId | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
pPose | The pose of the object. |
pScores | A vector holding the scores of the single terms. |
pQualityOfMatch | Indicator 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
-
pStatus | True, to select the scene object as the one with the best score. |
Definition at line 113 of file KinematicChainVisualizer.cpp.
bool Visualization::KinematicChainVisualizer::mBestStatus |
|
private |
The documentation for this class was generated from the following files: