AUTh-ARL Core Stack  0.7
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
arl::viz::RVisualizer Class Reference

This class implements visualization functionalities for RViz. More...

#include <rvisualizer.h>

Inheritance diagram for arl::viz::RVisualizer:
Collaboration diagram for arl::viz::RVisualizer:

Public Member Functions

 RVisualizer ()
 The default constructor which initializes the object with the default topic and base frame. More...
 
 RVisualizer (const std::string &base_frame, const std::string &rviz_topic=DEFAULT_RVIZ_TOPIC)
 The constructor used in order to specify different base frame or topic than the defaults. More...
 
template<typename T >
void visualizePath (const std::vector< T > &points, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double radius=0.01, double alpha=1, double lifetime=0)
 Visualizes a set of points as a connected path in RViz. The points can be any type which implements the operator(). More...
 
template<typename T >
void visualizeSphere (const T &center, const double radius, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a a sphere in RViz. The center of the sphere can be any type which implements the operator(). More...
 
template<typename T >
void visualizeSpheres (const std::vector< T > &centers, const std::vector< double > &radii, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a set of spheres in RViz. The centers of the sphere can be any type which implements the operator(). More...
 
void visualizeFrame (const arma::mat &pose, double length=0.1, double width=0.01, double alpha=1, double lifetime=0)
 Visualizes an armadillo frame given as a 3x4 homogeneous transformation, having the rotation matrix in the first 3 columns and the position of the origin on the last column. More...
 
void visualizeFrame (const KDL::Frame &pose, double length=0.1, double radius=0.01, double alpha=1, double lifetime=0)
 Visualizes a KDL frame. More...
 
void visualizeText (const arma::mat &pose, const std::string &text, rviz_visual_tools::colors color=rviz_visual_tools::colors::WHITE, rviz_visual_tools::scales scale=rviz_visual_tools::scales::REGULAR, double alpha=1, double lifetime=0)
 
template<typename T >
void visualizeCylinder (const T &point_1, const T &point_2, const double radius, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a cylinder in RViz. Needs a line segment in space (two points) which implement the operator() and its radius. More...
 
template<typename T >
void visualizeVector (const T &start, const T &end, double width=0.05, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a vector/arrow in RViz. Needs two 3D points in space which represent the start and the the end of the vector. More...
 
template<typename T >
void visualizeBox (const T &top, const T &bottom, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a cuboid (a paralliped box) in RViz. Needs two 3D points in space which represent the top corner of the box and the bottom opposite corner. More...
 
template<typename T >
void visualizeLine (const T &start, const T &end, rviz_visual_tools::colors color=rviz_visual_tools::colors::RED, double alpha=1, double lifetime=0)
 Visualizes a line segment in RViz. More...
 

Public Attributes

visualization_msgs::Marker vector_marker_
 

Detailed Description

This class implements visualization functionalities for RViz.

Attention
This class provides API with ROS which does not guarantee real-time performace. This means that calling a function of this class does not guarantee that it will return quickly or in a predictable time, as it interfaces with ROS topics. If you want to visualize data from a robot controller which runs in real H/W, please do it from a seperate thread and not inside the thread of your controller.

Constructor & Destructor Documentation

arl::viz::RVisualizer::RVisualizer ( )

The default constructor which initializes the object with the default topic and base frame.

arl::viz::RVisualizer::RVisualizer ( const std::string &  base_frame,
const std::string &  rviz_topic = DEFAULT_RVIZ_TOPIC 
)

The constructor used in order to specify different base frame or topic than the defaults.

Parameters
base_frameThe name of the base frame
rviz_topicThe name of the ROS topic

Member Function Documentation

template<typename T >
void arl::viz::RVisualizer::visualizeBox ( const T &  top,
const T &  bottom,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a cuboid (a paralliped box) in RViz. Needs two 3D points in space which represent the top corner of the box and the bottom opposite corner.

Parameters
topThe top corner of the box
bottomThe bottom corner of the box
colorThe color of the path defined in the enum rviz_visual_tools::colors.
alphaThe opacity of the path from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time
template<typename T >
void arl::viz::RVisualizer::visualizeCylinder ( const T &  point_1,
const T &  point_2,
const double  radius,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a cylinder in RViz. Needs a line segment in space (two points) which implement the operator() and its radius.

Parameters
point_1The first point of the line segment
point_2The second point of the line segment
radiusThe radius of the cylinder in m
colorThe color of the path defined in the enum rviz_visual_tools::colors.
alphaThe opacity of the path from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time
void arl::viz::RVisualizer::visualizeFrame ( const arma::mat &  pose,
double  length = 0.1,
double  width = 0.01,
double  alpha = 1,
double  lifetime = 0 
)

Visualizes an armadillo frame given as a 3x4 homogeneous transformation, having the rotation matrix in the first 3 columns and the position of the origin on the last column.

Parameters
poseThe homogeneous transformation
lengthThe length of the axes
widthThe width of the axes
alphaThe opacity from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time

Here is the call graph for this function:

void arl::viz::RVisualizer::visualizeFrame ( const KDL::Frame &  pose,
double  length = 0.1,
double  radius = 0.01,
double  alpha = 1,
double  lifetime = 0 
)

Visualizes a KDL frame.

Parameters
poseThe pose of the frame
lengthThe length of the axes
widthThe width of the axes
alphaThe opacity from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time

Here is the call graph for this function:

template<typename T >
void arl::viz::RVisualizer::visualizeLine ( const T &  start,
const T &  end,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a line segment in RViz.

Parameters
startThe first point of the line segment. Any 3d-vector that implements operator().
endThe second point of the line segment. Any 3d-vector that implements operator().
colorIts color. Available colors in rviz_visual_tools.
alphaIts opacity.
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time.
template<typename T >
void arl::viz::RVisualizer::visualizePath ( const std::vector< T > &  points,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  radius = 0.01,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a set of points as a connected path in RViz. The points can be any type which implements the operator().

Parameters
pointsThe set of points to be visualized
colorThe color of the path defined in the enum rviz_visual_tools::colors.
radiusThe width of path
alphaThe opacity of the path from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time
template<typename T >
void arl::viz::RVisualizer::visualizeSphere ( const T &  center,
const double  radius,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a a sphere in RViz. The center of the sphere can be any type which implements the operator().

Parameters
centerThe center of the sphere in m
radiusThe radius of the sphere in m
colorThe color of the path defined in the enum rviz_visual_tools::colors.
alphaThe opacity of the path from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time
template<typename T >
void arl::viz::RVisualizer::visualizeSpheres ( const std::vector< T > &  centers,
const std::vector< double > &  radii,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a set of spheres in RViz. The centers of the sphere can be any type which implements the operator().

Parameters
centersA vector with the centers of the sphere in m
radiiThe radii of the spheres in m
colorThe color of the path defined in the enum rviz_visual_tools::colors.
alphaThe opacity of the path from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time
void arl::viz::RVisualizer::visualizeText ( const arma::mat &  pose,
const std::string &  text,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::WHITE,
rviz_visual_tools::scales  scale = rviz_visual_tools::scales::REGULAR,
double  alpha = 1,
double  lifetime = 0 
)

Here is the call graph for this function:

template<typename T >
void arl::viz::RVisualizer::visualizeVector ( const T &  start,
const T &  end,
double  width = 0.05,
rviz_visual_tools::colors  color = rviz_visual_tools::colors::RED,
double  alpha = 1,
double  lifetime = 0 
)
inline

Visualizes a vector/arrow in RViz. Needs two 3D points in space which represent the start and the the end of the vector.

Parameters
startThe start of the vector
endThe end of the vector
widthThe width of the vector
colorThe color of the path defined in the enum rviz_visual_tools::colors.
alphaThe opacity from 0 to 1
lifetimeThe amount of time to be visualized in seconds. 0 stands for infinite time

Member Data Documentation

visualization_msgs::Marker arl::viz::RVisualizer::vector_marker_