#include <GaussianVisualization.h>
Public Member Functions | |
| GaussianVisualization () | |
| visualization_msgs::Marker | generateArrowToPoint (const int pMarkerID, const std_msgs::ColorRGBA &pColor, const boost::shared_ptr< Eigen::Quaternion< double > > pPoint) |
| boost::shared_ptr< visualization_msgs::Marker > | generateCovarianceEllipsoidMarker (const int pMarkerID, const int pMarkerShape, const std::vector< std::vector< std::vector< float > > > &pWireFramePolygons, const float &pWireFrameWidth, const std_msgs::ColorRGBA &pEllipsoidColor) |
| visualization_msgs::Marker | generatePointCloudPoint (const int pMarkerID, const unsigned int pId, const boost::shared_ptr< Eigen::Quaternion< double > > &pPoint) |
| void | publishArrowToPoint (const int pMarkerID, const std_msgs::ColorRGBA &pColor, const boost::shared_ptr< Eigen::Quaternion< double > > pPoint) |
| void | publishCovarianceEllipsoidCoordinateSystemMarker (const int pMarkerID) |
| void | publishCovarianceEllipsoidMarker (const int pMarkerID, const std_msgs::ColorRGBA &pEllipsoidColor) |
| void | publishPointCloud (const int pMarkerID, const std::vector< boost::shared_ptr< Eigen::Quaternion< double > > > pCloud) |
| void | setAlphaChannel (const float pAlphaChannel) |
| void | setKernel (const boost::shared_ptr< Eigen::Vector3d > &pMean, const boost::shared_ptr< Eigen::Matrix3d > &pCovariance) |
| void | setObjectLocationFrameID (const std::string &pObjectLocationFrameID) |
| void | setScaleFactor (double pScale) |
| void | setSigmaMultiplicator (const float pSigmaMultiplicator) |
| template<class T > | |
| void | stlVectorToPointMsg (const std::vector< T > pPositionVector, geometry_msgs::Point &pROSPositionMsg) |
| ~GaussianVisualization () | |
Private Attributes | |
| float | mAlphaChannel |
| boost::shared_ptr< Eigen::Matrix3d > | mCovariance |
| ros::NodeHandle | mHandle |
| boost::shared_ptr< Eigen::Vector3d > | mMean |
| std::string | mObjectLocationFrameID |
| boost::shared_ptr< ros::Publisher > | mPublisher |
| double | mScale |
| float | mSigmaMultiplicator |
Visualizer class for 3D gaussian normal distributions.
Definition at line 45 of file GaussianVisualization.h.
| Visualization::GaussianVisualization::GaussianVisualization | ( | ) |
Constructor.
Definition at line 22 of file GaussianVisualization.cpp.
| Visualization::GaussianVisualization::~GaussianVisualization | ( | ) |
Destructor.
Definition at line 29 of file GaussianVisualization.cpp.
| visualization_msgs::Marker Visualization::GaussianVisualization::generateArrowToPoint | ( | const int | pMarkerID, |
| const std_msgs::ColorRGBA & | pColor, | ||
| const boost::shared_ptr< Eigen::Quaternion< double > > | pPoint | ||
| ) |
Create a visualization marker message that contains an arrow pointing perpendicular to the given point.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pColor | Color of the arrow. Specified as r/g/b/a vector, with values in the range of [0, 1]. |
| pPoint | The point to point to ;). |
Definition at line 266 of file GaussianVisualization.cpp.
| boost::shared_ptr< visualization_msgs::Marker > Visualization::GaussianVisualization::generateCovarianceEllipsoidMarker | ( | const int | pMarkerID, |
| const int | pMarkerShape, | ||
| const std::vector< std::vector< std::vector< float > > > & | pWireFramePolygons, | ||
| const float & | pWireFrameWidth, | ||
| const std_msgs::ColorRGBA & | pEllipsoidColor | ||
| ) |
Calculates covariance ellipsoid from a parametric description of an nD normal distribution. Parameterizes a spherical shaped marker message using mean of distribution, calculated ellipsoid and other parameters of this function.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pMarkerShape | Should be either visualization_msgs::Marker::SPHERE for surface model or LINE_STRIP for wire-frame model. |
| pWireFramePolygons | Contour polygons (middle) containing 3D points (inner) approximating ellipses in the three (outer vector) coordinate planes with normals in x/y/z order. Assign emtpy vector if surface model should be generated. |
| pWireFrameWidth | Sets the width of the lines representing wire-frame. Ignored if surface model is desired. |
| pEllipsoidColor | Color of the ellipsoid. Specified as r/g/b/a vector, with values in the range of [0, 1]. |
Definition at line 74 of file GaussianVisualization.cpp.
| visualization_msgs::Marker Visualization::GaussianVisualization::generatePointCloudPoint | ( | const int | pMarkerID, |
| const unsigned int | pId, | ||
| const boost::shared_ptr< Eigen::Quaternion< double > > & | pPoint | ||
| ) |
Create a visualization marker message that contains a point of the point cloud.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pId | The number of the point in the cloud. |
| pPoint | The point to visualize. |
Definition at line 328 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::publishArrowToPoint | ( | const int | pMarkerID, |
| const std_msgs::ColorRGBA & | pColor, | ||
| const boost::shared_ptr< Eigen::Quaternion< double > > | pPoint | ||
| ) |
Create a visualization marker message that contains an arrow pointing perpendicular to the given point and publishes it.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pColor | Color of the arrow. Specified as r/g/b/a vector, with values in the range of [0, 1]. |
| pPoint | The point to point to ;). |
Definition at line 256 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::publishCovarianceEllipsoidCoordinateSystemMarker | ( | const int | pMarkerID | ) |
Visualizes the eigenvectors of the covariance matrix which are also the coordinate system of the covariance ellipse.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
Definition at line 199 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::publishCovarianceEllipsoidMarker | ( | const int | pMarkerID, |
| const std_msgs::ColorRGBA & | pEllipsoidColor | ||
| ) |
Calculates covariance ellipsoid from a parametric description of an nD normal distribution. Parameterizes a spherical shaped marker message using mean of distribution, calculated ellipsoid and other parameters of this function. Sends marker message under topic set by publisher argument of function to visualize a hull for some distribution samples.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pEllipsoidColor | Color of the ellipsoid. Specified as r/g/b/a vector, with values in the range of [0, 1]. |
Definition at line 64 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::publishPointCloud | ( | const int | pMarkerID, |
| const std::vector< boost::shared_ptr< Eigen::Quaternion< double > > > | pCloud | ||
| ) |
Create a visualization marker message that contains the point cloud.
| pMarkerID | Serves as unique id for the marker. Any marker sent with the same id will overwrite the old one. |
| pCloud | The point cloud to visualize. |
Definition at line 317 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::setAlphaChannel | ( | const float | pAlphaChannel | ) |
Setter function for mAlphaChannel.
| pAlphaChannel | Sets transparency of visualized covariance ellipsoid. |
Definition at line 49 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::setKernel | ( | const boost::shared_ptr< Eigen::Vector3d > & | pMean, |
| const boost::shared_ptr< Eigen::Matrix3d > & | pCovariance | ||
| ) |
Setter function for the mean vector and covariance matrix of the kernel.
| pCovariance | A 3x3 eigen matrix representing the corvariance matrix of the gaussian kernel. |
| pMean | A 3d eigen vector representing the mean of the gaussian kernel. |
Definition at line 33 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::setObjectLocationFrameID | ( | const std::string & | pObjectLocationFrameID | ) |
Setter function for mObjectLocationFrameID.
| pObjectLocationFrameID | Identifier for coordinate frame relative to which visualized covariance ellipsoid are defined. |
Definition at line 44 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::setScaleFactor | ( | double | pScale | ) |
The covariance ellipses tend to be very small, therefore a scaling factor shall be applied to it.
| pScale | Factor to multiply the kernel with. |
Definition at line 39 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::setSigmaMultiplicator | ( | const float | pSigmaMultiplicator | ) |
Setter function for mSigmaMultiplicator.
| pSigmaMultiplicator | Scaling factor for the size of the visualized covariance ellipsoid. |
Definition at line 54 of file GaussianVisualization.cpp.
| void Visualization::GaussianVisualization::stlVectorToPointMsg | ( | const std::vector< T > | pPositionVector, |
| geometry_msgs::Point & | pROSPositionMsg | ||
| ) |
Converts a 3D std::vector<T> of arbitrary compatible type T into a geometry_msgs/Point.msg from ROS.
| pPositionVector | STL representation of vector consisting of concatenated cartesian coordinates. |
| pROSPositionMsg | ROS message containing position information as cartesian point in 3D space. |
Definition at line 374 of file GaussianVisualization.cpp.
|
private |
Degree of transparency of ellipsoid visualized in rviz. Specified with values in the range of [0, 1] standing for increasing opacity.
Definition at line 200 of file GaussianVisualization.h.
|
private |
The covariance matrix of the multivariate gaussian.
Definition at line 190 of file GaussianVisualization.h.
|
private |
Node handle for inintializing the publisher.
Definition at line 170 of file GaussianVisualization.h.
|
private |
The mean vector of the multivariate gaussian.
Definition at line 185 of file GaussianVisualization.h.
|
private |
ROS tf coordinate frame relative to which all processed pose information shall be interpreted.
Definition at line 195 of file GaussianVisualization.h.
|
private |
Publisher for the visualization messages containing the covariance ellipses and position marker for observed objects.
Definition at line 175 of file GaussianVisualization.h.
|
private |
The factor to multiply the kernel with to make it look bigger.
Definition at line 180 of file GaussianVisualization.h.
|
private |
Lengths of half-axes of the ellipsoid are pSigmaMultiplicator times the standard deviations associated to the coordinate axes of the ellipsoid.
Definition at line 205 of file GaussianVisualization.h.