mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
library for drawing large amounts of geometric objects in RVIZ at the same time More...
#include <batch_visualizer.h>
Public Member Functions | |
BatchVisualizer () | |
dummy constructor | |
~BatchVisualizer () | |
destructor | |
BatchVisualizer (ros::NodeHandle &nh, std::string marker_topic_name, std::string parent_frame) | |
constructor to initialize the visualizer More... | |
void | addPoint (const Eigen::Vector3d &point, const double r=0.0, const double g=1.0, const double b=0.3, const double a=1.0, const ros::Duration &timeout=ros::Duration(0)) |
add a point to the buffer More... | |
void | addRay (const mrs_lib::geometry::Ray &ray, const double r=1.0, const double g=0.0, const double b=0.0, const double a=1.0, const ros::Duration &timeout=ros::Duration(0)) |
add a ray to the buffer More... | |
void | addTriangle (const mrs_lib::geometry::Triangle &tri, const double r=0.5, const double g=0.5, const double b=0.0, const double a=1.0, const bool filled=true, const ros::Duration &timeout=ros::Duration(0)) |
add a triangle to the buffer More... | |
void | addRectangle (const mrs_lib::geometry::Rectangle &rect, const double r=0.5, const double g=0.5, const double b=0.0, const double a=1.0, const bool filled=true, const ros::Duration &timeout=ros::Duration(0)) |
add a rectangle to the buffer More... | |
void | addCuboid (const mrs_lib::geometry::Cuboid &cuboid, const double r=0.5, const double g=0.5, const double b=0.0, const double a=1.0, const bool filled=true, const ros::Duration &timeout=ros::Duration(0)) |
add a cuboid to the buffer More... | |
void | addEllipse (const mrs_lib::geometry::Ellipse &ellipse, const double r=0.0, const double g=1.0, const double b=1.0, const double a=1.0, const bool filled=true, const int num_points=DEFAULT_ELLIPSE_POINTS, const ros::Duration &timeout=ros::Duration(0)) |
add an ellipse to the buffer More... | |
void | addCylinder (const mrs_lib::geometry::Cylinder &cylinder, const double r=0.7, const double g=0.8, const double b=0.3, const double a=1.0, const bool filled=true, const bool capped=true, const int sides=DEFAULT_ELLIPSE_POINTS, const ros::Duration &timeout=ros::Duration(0)) |
add a cylinder to the buffer More... | |
void | addCone (const mrs_lib::geometry::Cone &cone, const double r=0.7, const double g=0.8, const double b=0.3, const double a=1.0, const bool filled=true, const bool capped=true, const int sides=DEFAULT_ELLIPSE_POINTS, const ros::Duration &timeout=ros::Duration(0)) |
add a cone to the buffer More... | |
void | addPath (const mrs_msgs::Path &p, const double r=0.3, const double g=1.0, const double b=0.3, const double a=1.0, const bool filled=true, const ros::Duration &timeout=ros::Duration(0)) |
add a path to the buffer More... | |
void | addTrajectory (const mrs_msgs::TrajectoryReference &traj, const double r=0.3, const double g=1.0, const double b=0.3, const double a=1.0, const bool filled=true, const ros::Duration &timeout=ros::Duration(0)) |
add a trajectory to the buffer More... | |
void | addNullPoint () |
helper function for adding an invisible point to the object buffer | |
void | addNullLine () |
helper function for adding an invisible line to the object buffer | |
void | addNullTriangle () |
helper function for adding an invisible triangle to the buffer | |
void | setPointsScale (const double scale) |
set the scale of all points More... | |
void | setParentFrame (const std::string parent_frame) |
set the parent frame_id More... | |
void | setLinesScale (const double scale) |
set the thickness of all lines More... | |
void | clearBuffers () |
remove all objects from the buffer | |
void | clearVisuals () |
publishes an empty message. Removes all objects drawn onto the scene, but keeps them in buffer | |
void | publish () |
publish the visual markers ROS message and populates it with buffer content | |
library for drawing large amounts of geometric objects in RVIZ at the same time
mrs_lib::BatchVisualizer::BatchVisualizer | ( | ros::NodeHandle & | nh, |
std::string | marker_topic_name, | ||
std::string | parent_frame | ||
) |
constructor to initialize the visualizer
nh | ROS node to connect our publisher to ROS |
marker_topic_name | name of the topic on which the markers will be published |
parent_frame | name of the frame to which the markers will be linked |
void mrs_lib::BatchVisualizer::addCone | ( | const mrs_lib::geometry::Cone & | cone, |
const double | r = 0.7 , |
||
const double | g = 0.8 , |
||
const double | b = 0.3 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const bool | capped = true , |
||
const int | sides = DEFAULT_ELLIPSE_POINTS , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a cone to the buffer
cone | cone to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
capped | bool to set caps on/off. True = cap drawn, False = base cap missing |
sides | number of points to approximate the round shape |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addCuboid | ( | const mrs_lib::geometry::Cuboid & | cuboid, |
const double | r = 0.5 , |
||
const double | g = 0.5 , |
||
const double | b = 0.0 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a cuboid to the buffer
cuboid | cuboid to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addCylinder | ( | const mrs_lib::geometry::Cylinder & | cylinder, |
const double | r = 0.7 , |
||
const double | g = 0.8 , |
||
const double | b = 0.3 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const bool | capped = true , |
||
const int | sides = DEFAULT_ELLIPSE_POINTS , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a cylinder to the buffer
cylinder | cylinder to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
capped | bool to set caps on/off. True = caps drawn, False = hollow cylinder |
sides | number of points to approximate the round shape |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addEllipse | ( | const mrs_lib::geometry::Ellipse & | ellipse, |
const double | r = 0.0 , |
||
const double | g = 1.0 , |
||
const double | b = 1.0 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const int | num_points = DEFAULT_ELLIPSE_POINTS , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add an ellipse to the buffer
ellipse | ellipse to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
num_points | number of points to approximate the round shape |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addPath | ( | const mrs_msgs::Path & | p, |
const double | r = 0.3 , |
||
const double | g = 1.0 , |
||
const double | b = 0.3 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a path to the buffer
p | path to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = continuous line, False = only visualize points |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addPoint | ( | const Eigen::Vector3d & | point, |
const double | r = 0.0 , |
||
const double | g = 1.0 , |
||
const double | b = 0.3 , |
||
const double | a = 1.0 , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a point to the buffer
point | coordinates of the point |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addRay | ( | const mrs_lib::geometry::Ray & | ray, |
const double | r = 1.0 , |
||
const double | g = 0.0 , |
||
const double | b = 0.0 , |
||
const double | a = 1.0 , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a ray to the buffer
ray | ray to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addRectangle | ( | const mrs_lib::geometry::Rectangle & | rect, |
const double | r = 0.5 , |
||
const double | g = 0.5 , |
||
const double | b = 0.0 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a rectangle to the buffer
rect | rectangle to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addTrajectory | ( | const mrs_msgs::TrajectoryReference & | traj, |
const double | r = 0.3 , |
||
const double | g = 1.0 , |
||
const double | b = 0.3 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a trajectory to the buffer
traj | trajectory reference to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = continuous line, False = only visualize points |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::addTriangle | ( | const mrs_lib::geometry::Triangle & | tri, |
const double | r = 0.5 , |
||
const double | g = 0.5 , |
||
const double | b = 0.0 , |
||
const double | a = 1.0 , |
||
const bool | filled = true , |
||
const ros::Duration & | timeout = ros::Duration(0) |
||
) |
add a triangle to the buffer
tri | triangle to be added |
r | red color in range <0,1> |
g | green color in range <0,1> |
b | blue color in range <0,1> |
a | alpha in range <0,1> (0 is fully transparent) |
filled | bool to set fill. True = face visible, False = outline visible |
timeout | time in seconds after which the object should be removed from buffer |
void mrs_lib::BatchVisualizer::setLinesScale | ( | const double | scale | ) |
set the thickness of all lines
scale |
void mrs_lib::BatchVisualizer::setParentFrame | ( | const std::string | parent_frame | ) |
set the parent frame_id
parent_frame |
void mrs_lib::BatchVisualizer::setPointsScale | ( | const double | scale | ) |
set the scale of all points
scale |