AUTh-ARL Core Stack
0.7
|
This class implements visualization functionalities for RViz. More...
#include <rvisualizer.h>
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 ¢er, 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 > ¢ers, 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_ |
This class implements visualization functionalities for RViz.
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.
base_frame | The name of the base frame |
rviz_topic | The name of the ROS topic |
|
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.
top | The top corner of the box |
bottom | The bottom corner of the box |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
alpha | The opacity of the path from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
|
inline |
Visualizes a cylinder in RViz. Needs a line segment in space (two points) which implement the operator() and its radius.
point_1 | The first point of the line segment |
point_2 | The second point of the line segment |
radius | The radius of the cylinder in m |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
alpha | The opacity of the path from 0 to 1 |
lifetime | The 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.
pose | The homogeneous transformation |
length | The length of the axes |
width | The width of the axes |
alpha | The opacity from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
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.
pose | The pose of the frame |
length | The length of the axes |
width | The width of the axes |
alpha | The opacity from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
|
inline |
Visualizes a line segment in RViz.
start | The first point of the line segment. Any 3d-vector that implements operator(). |
end | The second point of the line segment. Any 3d-vector that implements operator(). |
color | Its color. Available colors in rviz_visual_tools. |
alpha | Its opacity. |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time. |
|
inline |
Visualizes a set of points as a connected path in RViz. The points can be any type which implements the operator().
points | The set of points to be visualized |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
radius | The width of path |
alpha | The opacity of the path from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
|
inline |
Visualizes a a sphere in RViz. The center of the sphere can be any type which implements the operator().
center | The center of the sphere in m |
radius | The radius of the sphere in m |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
alpha | The opacity of the path from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
|
inline |
Visualizes a set of spheres in RViz. The centers of the sphere can be any type which implements the operator().
centers | A vector with the centers of the sphere in m |
radii | The radii of the spheres in m |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
alpha | The opacity of the path from 0 to 1 |
lifetime | The 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 |
||
) |
|
inline |
Visualizes a vector/arrow in RViz. Needs two 3D points in space which represent the start and the the end of the vector.
start | The start of the vector |
end | The end of the vector |
width | The width of the vector |
color | The color of the path defined in the enum rviz_visual_tools::colors. |
alpha | The opacity from 0 to 1 |
lifetime | The amount of time to be visualized in seconds. 0 stands for infinite time |
visualization_msgs::Marker arl::viz::RVisualizer::vector_marker_ |