Enumerations | |
enum | Color : uint8_t { BLACK = 0, BROWN = 1, BLUE = 2, CYAN = 3, GREY = 4, DARK_GREY = 5, GREEN = 6, LIME_GREEN = 7, MAGENTA = 8, ORANGE = 9, PURPLE = 10, RED = 11, PINK = 12, WHITE = 13, YELLOW = 14 } |
Functions | |
template<typename T > | |
void | appendFrame (T &container, const geometry_msgs::PoseStamped &pose, double scale=1.0, const std::string &ns="frame", double diameter_fraction=0.1) |
std_msgs::ColorRGBA & | brighten (std_msgs::ColorRGBA &color, double fraction) |
geometry_msgs::Pose | composePoses (const Eigen::Isometry3d &first, const geometry_msgs::Pose &second) |
geometry_msgs::Pose | composePoses (const geometry_msgs::Pose &first, const Eigen::Isometry3d &second) |
std_msgs::ColorRGBA & | darken (std_msgs::ColorRGBA &color, double fraction) |
std_msgs::ColorRGBA | getColor (Color color, double alpha=1.0) |
double | interpolate (double start, double end, double fraction) |
std_msgs::ColorRGBA & | interpolate (std_msgs::ColorRGBA &color, const std_msgs::ColorRGBA &other, double fraction) |
visualization_msgs::Marker & | makeArrow (visualization_msgs::Marker &m, const Eigen::Vector3d &start_point, const Eigen::Vector3d &end_point, double diameter, double head_length=0.0) |
create an arrow with a start and end point More... | |
visualization_msgs::Marker & | makeArrow (visualization_msgs::Marker &m, double scale=1.0, bool tip_at_origin=false) |
create an arrow along x-axis More... | |
vm::Marker & | makeArrow (vm::Marker &m, const Eigen::Vector3d &start_point, const Eigen::Vector3d &end_point, double diameter, double head_length) |
vm::Marker & | makeArrow (vm::Marker &m, double scale, bool tip_at_origin) |
visualization_msgs::Marker & | makeBox (visualization_msgs::Marker &m, double x, double y, double z) |
create a box with given dimensions along x, y, z axes More... | |
vm::Marker & | makeBox (vm::Marker &m, double x, double y, double z) |
vm::Marker | makeCone (double angle, vm::Marker &m) |
create a cone of given angle along the x-axis More... | |
visualization_msgs::Marker & | makeCone (visualization_msgs::Marker &m, double angle) |
create a cone of given angle along the x-axis More... | |
visualization_msgs::Marker & | makeCylinder (visualization_msgs::Marker &m, double diameter, double height) |
create a cylinder along z-axis More... | |
vm::Marker & | makeCylinder (vm::Marker &m, double diameter, double height) |
visualization_msgs::Marker & | makeFromGeometry (visualization_msgs::Marker &m, const urdf::Geometry &geom) |
create marker from urdf::Geom More... | |
vm::Marker & | makeFromGeometry (vm::Marker &m, const urdf::Geometry &geom) |
visualization_msgs::Marker & | makeMesh (visualization_msgs::Marker &m, const std::string &filename, double scale) |
visualization_msgs::Marker & | makeMesh (visualization_msgs::Marker &m, const std::string &filename, double sx=1.0, double sy=1.0, double sz=1.0) |
create a mesh marker More... | |
vm::Marker & | makeMesh (vm::Marker &m, const std::string &filename, double sx, double sy, double sz) |
visualization_msgs::Marker & | makeSphere (visualization_msgs::Marker &m, double radius=1.0) |
vm::Marker & | makeSphere (vm::Marker &m, double radius) |
visualization_msgs::Marker & | makeText (visualization_msgs::Marker &m, const std::string &text) |
create text marker More... | |
vm::Marker & | makeText (vm::Marker &m, const std::string &text) |
visualization_msgs::Marker & | makeXYPlane (visualization_msgs::Marker &m) |
create planes with corners (-1,-1) - (+1,+1) More... | |
vm::Marker & | makeXYPlane (vm::Marker &m) |
visualization_msgs::Marker & | makeXZPlane (visualization_msgs::Marker &m) |
vm::Marker & | makeXZPlane (vm::Marker &m) |
visualization_msgs::Marker & | makeYZPlane (visualization_msgs::Marker &m) |
vm::Marker & | makeYZPlane (vm::Marker &m) |
void | prepareMarker (vm::Marker &m, int marker_type) |
std_msgs::ColorRGBA & | setColor (std_msgs::ColorRGBA &color, Color color_id, double alpha=1.0) |
enum rviz_marker_tools::Color : uint8_t |
Enumerator | |
---|---|
BLACK | |
BROWN | |
BLUE | |
CYAN | |
GREY | |
DARK_GREY | |
GREEN | |
LIME_GREEN | |
MAGENTA | |
ORANGE | |
PURPLE | |
RED | |
PINK | |
WHITE | |
YELLOW |
Definition at line 14 of file marker_creation.h.
void rviz_marker_tools::appendFrame | ( | T & | container, |
const geometry_msgs::PoseStamped & | pose, | ||
double | scale = 1.0 , |
||
const std::string & | ns = "frame" , |
||
double | diameter_fraction = 0.1 |
||
) |
Definition at line 83 of file marker_creation.h.
std_msgs::ColorRGBA & rviz_marker_tools::brighten | ( | std_msgs::ColorRGBA & | color, |
double | fraction | ||
) |
Definition at line 123 of file marker_creation.cpp.
geometry_msgs::Pose rviz_marker_tools::composePoses | ( | const Eigen::Isometry3d & | first, |
const geometry_msgs::Pose & | second | ||
) |
Definition at line 148 of file marker_creation.cpp.
geometry_msgs::Pose rviz_marker_tools::composePoses | ( | const geometry_msgs::Pose & | first, |
const Eigen::Isometry3d & | second | ||
) |
Definition at line 141 of file marker_creation.cpp.
std_msgs::ColorRGBA & rviz_marker_tools::darken | ( | std_msgs::ColorRGBA & | color, |
double | fraction | ||
) |
Definition at line 130 of file marker_creation.cpp.
std_msgs::ColorRGBA rviz_marker_tools::getColor | ( | Color | color, |
double | alpha = 1.0 |
||
) |
Definition at line 135 of file marker_creation.cpp.
double rviz_marker_tools::interpolate | ( | double | start, |
double | end, | ||
double | fraction | ||
) |
Definition at line 107 of file marker_creation.cpp.
std_msgs::ColorRGBA & rviz_marker_tools::interpolate | ( | std_msgs::ColorRGBA & | color, |
const std_msgs::ColorRGBA & | other, | ||
double | fraction | ||
) |
Definition at line 111 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeArrow | ( | visualization_msgs::Marker & | m, |
const Eigen::Vector3d & | start_point, | ||
const Eigen::Vector3d & | end_point, | ||
double | diameter, | ||
double | head_length = 0.0 |
||
) |
create an arrow with a start and end point
visualization_msgs::Marker& rviz_marker_tools::makeArrow | ( | visualization_msgs::Marker & | m, |
double | scale = 1.0 , |
||
bool | tip_at_origin = false |
||
) |
create an arrow along x-axis
vm::Marker& rviz_marker_tools::makeArrow | ( | vm::Marker & | m, |
const Eigen::Vector3d & | start_point, | ||
const Eigen::Vector3d & | end_point, | ||
double | diameter, | ||
double | head_length | ||
) |
Definition at line 271 of file marker_creation.cpp.
vm::Marker& rviz_marker_tools::makeArrow | ( | vm::Marker & | m, |
double | scale, | ||
bool | tip_at_origin | ||
) |
Definition at line 285 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeBox | ( | visualization_msgs::Marker & | m, |
double | x, | ||
double | y, | ||
double | z | ||
) |
create a box with given dimensions along x, y, z axes
vm::Marker& rviz_marker_tools::makeBox | ( | vm::Marker & | m, |
double | x, | ||
double | y, | ||
double | z | ||
) |
Definition at line 246 of file marker_creation.cpp.
vm::Marker rviz_marker_tools::makeCone | ( | double | angle, |
vm::Marker & | m | ||
) |
create a cone of given angle along the x-axis
Definition at line 214 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeCone | ( | visualization_msgs::Marker & | m, |
double | angle | ||
) |
create a cone of given angle along the x-axis
visualization_msgs::Marker& rviz_marker_tools::makeCylinder | ( | visualization_msgs::Marker & | m, |
double | diameter, | ||
double | height | ||
) |
create a cylinder along z-axis
vm::Marker& rviz_marker_tools::makeCylinder | ( | vm::Marker & | m, |
double | diameter, | ||
double | height | ||
) |
Definition at line 254 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeFromGeometry | ( | visualization_msgs::Marker & | m, |
const urdf::Geometry & | geom | ||
) |
create marker from urdf::Geom
vm::Marker& rviz_marker_tools::makeFromGeometry | ( | vm::Marker & | m, |
const urdf::Geometry & | geom | ||
) |
Definition at line 301 of file marker_creation.cpp.
|
inline |
Definition at line 65 of file marker_creation.h.
visualization_msgs::Marker& rviz_marker_tools::makeMesh | ( | visualization_msgs::Marker & | m, |
const std::string & | filename, | ||
double | sx = 1.0 , |
||
double | sy = 1.0 , |
||
double | sz = 1.0 |
||
) |
create a mesh marker
vm::Marker& rviz_marker_tools::makeMesh | ( | vm::Marker & | m, |
const std::string & | filename, | ||
double | sx, | ||
double | sy, | ||
double | sz | ||
) |
Definition at line 261 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeSphere | ( | visualization_msgs::Marker & | m, |
double | radius = 1.0 |
||
) |
vm::Marker& rviz_marker_tools::makeSphere | ( | vm::Marker & | m, |
double | radius | ||
) |
Definition at line 240 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeText | ( | visualization_msgs::Marker & | m, |
const std::string & | text | ||
) |
create text marker
vm::Marker& rviz_marker_tools::makeText | ( | vm::Marker & | m, |
const std::string & | text | ||
) |
Definition at line 294 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeXYPlane | ( | visualization_msgs::Marker & | m | ) |
create planes with corners (-1,-1) - (+1,+1)
All routines only touch the geometry part of the marker pose, color, namespace, id, etc need to be set externally
vm::Marker& rviz_marker_tools::makeXYPlane | ( | vm::Marker & | m | ) |
Definition at line 166 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeXZPlane | ( | visualization_msgs::Marker & | m | ) |
vm::Marker& rviz_marker_tools::makeXZPlane | ( | vm::Marker & | m | ) |
Definition at line 197 of file marker_creation.cpp.
visualization_msgs::Marker& rviz_marker_tools::makeYZPlane | ( | visualization_msgs::Marker & | m | ) |
vm::Marker& rviz_marker_tools::makeYZPlane | ( | vm::Marker & | m | ) |
Definition at line 205 of file marker_creation.cpp.
void rviz_marker_tools::prepareMarker | ( | vm::Marker & | m, |
int | marker_type | ||
) |
Definition at line 155 of file marker_creation.cpp.
std_msgs::ColorRGBA & rviz_marker_tools::setColor | ( | std_msgs::ColorRGBA & | color, |
Color | color_id, | ||
double | alpha = 1.0 |
||
) |
Definition at line 10 of file marker_creation.cpp.