#include <rviz_visual_tools.h>
Public Member Functions | |
Eigen::Vector3d | convertPoint (const geometry_msgs::Point &point) |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient. | |
geometry_msgs::Point | convertPoint (const geometry_msgs::Vector3 &point) |
Convert a Vector3 to a geometry_msg Point Note: Not thread safe but very convenient. | |
geometry_msgs::Point | convertPoint (const Eigen::Vector3d &point) |
Convert a Eigen point to a geometry_msg Point Note: Not thread safe but very convenient. | |
Eigen::Vector3d | convertPoint32 (const geometry_msgs::Point32 &point) |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient. | |
geometry_msgs::Point32 | convertPoint32 (const Eigen::Vector3d &point) |
Convert an Eigen point to a 32 bit geometry_msg point Note: Not thread safe but very convenient. | |
Eigen::Affine3d | convertPoint32ToPose (const geometry_msgs::Point32 &point) |
Convert a geometry_msg point (32bit) to an Eigen pose Note: Not thread safe but very convenient. | |
geometry_msgs::Pose | convertPointToPose (const geometry_msgs::Point &point) |
Add an identity rotation matrix to make a point have a full pose. | |
Eigen::Affine3d | convertPointToPose (const Eigen::Vector3d &point) |
geometry_msgs::Pose | convertPose (const Eigen::Affine3d &pose) |
Convert an Eigen pose to a geometry_msg pose Note: Not thread safe but very convenient. | |
Eigen::Affine3d | convertPose (const geometry_msgs::Pose &pose) |
Convert a geometry_msg pose to an Eigen pose Note: Not thread safe but very convenient. | |
geometry_msgs::Point | convertPoseToPoint (const Eigen::Affine3d &pose) |
Convert an Eigen pose to a geometry_msg point Note: Not thread safe but very convenient. | |
std_msgs::ColorRGBA | createRandColor () |
Create a random color that is not too light. | |
bool | deleteAllMarkers () |
Tell Rviz to clear all markers on a particular display. Note: only works on ROS Indigo and newer. | |
void | enableBatchPublishing (bool enable=true) |
Enable batch publishing - useful for when many markers need to be published at once and the ROS topic can get overloaded. This collects all published markers into array and only publishes them with triggerBatchPublish() is called. | |
void | generateEmptyPose (geometry_msgs::Pose &pose) |
Create a pose of position (0,0,0) and quaternion (0,0,0,1) | |
void | generateRandomCuboid (geometry_msgs::Pose &cuboid_pose, double &depth, double &width, double &height, RandomPoseBounds pose_bounds=RandomPoseBounds(), RandomCuboidBounds cuboid_bounds=RandomCuboidBounds()) |
Create a random rectangular cuboid of some shape. | |
void | generateRandomPose (geometry_msgs::Pose &pose, RandomPoseBounds pose_bounds=RandomPoseBounds()) |
Create a random pose within bounds of random_pose_bounds_. | |
void | generateRandomPose (Eigen::Affine3d &pose, RandomPoseBounds pose_bounds=RandomPoseBounds()) |
const std::string | getBaseFrame () |
Get the base frame. | |
Eigen::Vector3d | getCenterPoint (Eigen::Vector3d a, Eigen::Vector3d b) |
Find the center between to points. | |
std_msgs::ColorRGBA | getColor (const colors &color) |
Get the RGB value of standard colors. | |
std_msgs::ColorRGBA | getColorScale (double value) |
Convert a value from [0,1] to a color Green->Red. | |
double | getGlobalScale () |
Getter for the global scale used for changing size of all markers. | |
const bool & | getPsychedelicMode () const |
Getter for PsychedelicMode. | |
colors | getRandColor () |
Get a random color from the list of hardcoded enum color types. | |
geometry_msgs::Vector3 | getScale (const scales &scale, bool arrow_scale=false, double marker_scale=1.0) |
Get the rviz marker scale of standard sizes. | |
Eigen::Affine3d | getVectorBetweenPoints (Eigen::Vector3d a, Eigen::Vector3d b) |
Create a vector that points from point a to point b. | |
void | loadMarkerPub (bool wait_for_subscriber=false, bool latched=false) |
Load publishers as needed. | |
bool | loadRvizMarkers () |
Pre-load rviz markers for better efficiency. | |
bool | posesEqual (const Eigen::Affine3d &pose1, const Eigen::Affine3d &pose2, const double &threshold=0.000001) |
Test if two Eigen poses are close enough. | |
bool | publishArrow (const Eigen::Affine3d &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1, const std::size_t &id=0) |
Display an arrow along the x-axis of a pose. | |
bool | publishArrow (const geometry_msgs::Pose &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1, const std::size_t &id=0) |
bool | publishArrow (const geometry_msgs::PoseStamped &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1, const std::size_t &id=0) |
bool | publishAxis (const geometry_msgs::Pose &pose, double length=0.1, double radius=0.01, const std::string &ns="Axis") |
Display a marker of a axis. | |
bool | publishAxis (const Eigen::Affine3d &pose, double length=0.1, double radius=0.01, const std::string &ns="Axis") |
bool | publishAxisLabeled (const Eigen::Affine3d &pose, const std::string &label, const scales &scale=SMALL, const colors &color=WHITE) |
Display a marker of a axis with a text label describing it. | |
bool | publishAxisLabeled (const geometry_msgs::Pose &pose, const std::string &label, const scales &scale=SMALL, const colors &color=WHITE) |
bool | publishBlock (const geometry_msgs::Pose &pose, const colors &color=BLUE, const double &block_size=0.1) |
Display a marker of a block. | |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | publishBlock (const Eigen::Affine3d &pose, const colors &color=BLUE, const double &block_size=0.1) |
bool | publishCone (const Eigen::Affine3d &pose, double angle, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
Display a cone of a given angle along the x-axis. | |
bool | publishCone (const geometry_msgs::Pose &pose, double angle, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
bool | publishCuboid (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color=BLUE) |
Display a rectangular cuboid. | |
bool | publishCuboid (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const colors &color=BLUE, const std::string &ns="Cuboid", const std::size_t &id=0) |
bool | publishCuboid (const geometry_msgs::Pose &pose, const double depth, const double width, const double height, const colors &color=BLUE) |
Display a rectangular cuboid. | |
bool | publishCuboid (const Eigen::Affine3d &pose, const double depth, const double width, const double height, const colors &color=BLUE) |
bool | publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color=BLUE, double radius=0.01, const std::string &ns="Cylinder") |
Display a marker of a cylinder. | |
bool | publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, double radius=0.01, const std::string &ns="Cylinder") |
bool | publishCylinder (const Eigen::Affine3d &pose, const colors &color=BLUE, double height=0.1, double radius=0.01, const std::string &ns="Cylinder") |
Display a marker of a cylinder. | |
bool | publishCylinder (const geometry_msgs::Pose &pose, const colors &color=BLUE, double height=0.1, double radius=0.01, const std::string &ns="Cylinder") |
bool | publishCylinder (const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, double height=0.1, double radius=0.01, const std::string &ns="Cylinder") |
bool | publishGraph (const graph_msgs::GeometryGraph &graph, const colors &color, double radius) |
Display a graph. | |
bool | publishLine (const Eigen::Affine3d &point1, const Eigen::Affine3d &point2, const colors &color=BLUE, const scales &scale=REGULAR) |
Display a marker of line. | |
bool | publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color=BLUE, const scales &scale=REGULAR) |
bool | publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color, const double &radius) |
bool | publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, const scales &scale=REGULAR) |
bool | publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, const double &radius) |
bool | publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const colors &color=BLUE, const scales &scale=REGULAR) |
bool | publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, const scales &scale=REGULAR) |
bool | publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 &scale) |
bool | publishMarker (visualization_msgs::Marker &marker) |
Display a visualization_msgs Marker of a custom type. Allows reuse of the ros publisher. | |
bool | publishMarkers (visualization_msgs::MarkerArray &markers) |
Display an array of markers, allows reuse of the ROS publisher. | |
bool | publishMesh (const Eigen::Affine3d &pose, const std::string &file_name, const colors &color=CLEAR, double scale=1, const std::string &ns="mesh", const std::size_t &id=0) |
Display a mesh from file. | |
bool | publishMesh (const geometry_msgs::Pose &pose, const std::string &file_name, const colors &color=CLEAR, double scale=1, const std::string &ns="mesh", const std::size_t &id=0) |
bool | publishPath (const std::vector< geometry_msgs::Point > &path, const colors &color=RED, const scales &scale=REGULAR, const std::string &ns="Path") |
Display a marker of a series of connected lines. | |
bool | publishPath (const std::vector< Eigen::Vector3d > &path, const colors &color=RED, const double radius=0.01, const std::string &ns="Path") |
bool | publishPolygon (const geometry_msgs::Polygon &polygon, const colors &color=RED, const scales &scale=REGULAR, const std::string &ns="Polygon") |
Display a marker of a polygon. | |
bool | publishSphere (const Eigen::Affine3d &pose, const colors &color=BLUE, const scales &scale=REGULAR, const std::string &ns="Sphere", const std::size_t &id=0) |
Display a marker of a sphere. | |
bool | publishSphere (const Eigen::Vector3d &point, const colors &color=BLUE, const scales &scale=REGULAR, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const Eigen::Vector3d &point, const colors &color, const double scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::Point &point, const colors &color=BLUE, const scales &scale=REGULAR, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::Pose &pose, const colors &color=BLUE, const scales &scale=REGULAR, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::Pose &pose, const colors &color, const double scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::Pose &pose, const colors &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const Eigen::Affine3d &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSphere (const geometry_msgs::PoseStamped &pose, const colors &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", const std::size_t &id=0) |
bool | publishSpheres (const std::vector< Eigen::Vector3d > &points, const colors &color=BLUE, const double scale=0.1, const std::string &ns="Spheres") |
Display a marker of a series of spheres. | |
bool | publishSpheres (const std::vector< geometry_msgs::Point > &points, const colors &color=BLUE, const double scale=0.1, const std::string &ns="Spheres") |
bool | publishSpheres (const std::vector< geometry_msgs::Point > &points, const colors &color=BLUE, const scales &scale=REGULAR, const std::string &ns="Spheres") |
bool | publishSpheres (const std::vector< geometry_msgs::Point > &points, const colors &color, const geometry_msgs::Vector3 &scale, const std::string &ns="Spheres") |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | publishTests () |
Run a simple test of all visual_tool's features. | |
bool | publishText (const Eigen::Affine3d &pose, const std::string &text, const colors &color=WHITE, const scales &scale=REGULAR, bool static_id=true) |
Display a marker of a text. | |
bool | publishText (const Eigen::Affine3d &pose, const std::string &text, const colors &color, const geometry_msgs::Vector3 scale, bool static_id=true) |
bool | publishText (const geometry_msgs::Pose &pose, const std::string &text, const colors &color=WHITE, const scales &scale=REGULAR, bool static_id=true) |
bool | publishText (const geometry_msgs::Pose &pose, const std::string &text, const colors &color, const geometry_msgs::Vector3 scale, bool static_id=true) |
bool | publishWireframeCuboid (const Eigen::Affine3d &pose, double depth, double width, double height, const rviz_visual_tools::colors &color=BLUE, const std::string &ns="Wireframe Cuboid", const std::size_t &id=0) |
Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box. | |
bool | publishWireframeCuboid (const Eigen::Affine3d &pose, const Eigen::Vector3d &min_point, const Eigen::Vector3d &max_point, const rviz_visual_tools::colors &color=BLUE, const std::string &ns="Wireframe Cuboid", const std::size_t &id=0) |
Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box. | |
bool | publishWireframeRectangle (const Eigen::Affine3d &pose, const double &height, const double &width, const colors &color=BLUE, const scales &scale=REGULAR, const std::size_t &id=0) |
Publish outline of a rectangle. | |
bool | publishWireframeRectangle (const Eigen::Affine3d &pose, const Eigen::Vector3d &p1, const Eigen::Vector3d &p2, const Eigen::Vector3d &p3, const Eigen::Vector3d &p4, const colors &color, const scales &scale) |
bool | publishXArrow (const Eigen::Affine3d &pose, const colors &color=RED, const scales &scale=REGULAR, double length=0.1) |
Display an arrow along the x-axis of a pose. | |
bool | publishXArrow (const geometry_msgs::Pose &pose, const colors &color=RED, const scales &scale=REGULAR, double length=0.1) |
bool | publishXArrow (const geometry_msgs::PoseStamped &pose, const colors &color=RED, const scales &scale=REGULAR, double length=0.1) |
bool | publishXYPlane (const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
Display the XY plane of a given pose. | |
bool | publishXYPlane (const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
bool | publishXZPlane (const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
Display the XY plane of a given pose. | |
bool | publishXZPlane (const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
bool | publishYArrow (const Eigen::Affine3d &pose, const colors &color=GREEN, const scales &scale=REGULAR, double length=0.1) |
Display an arrow along the y-axis of a pose. | |
bool | publishYArrow (const geometry_msgs::Pose &pose, const colors &color=GREEN, const scales &scale=REGULAR, double length=0.1) |
bool | publishYArrow (const geometry_msgs::PoseStamped &pose, const colors &color=GREEN, const scales &scale=REGULAR, double length=0.1) |
bool | publishYZPlane (const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
Display the XY plane of a given pose. | |
bool | publishYZPlane (const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color=TRANSLUCENT, double scale=1.0) |
bool | publishZArrow (const Eigen::Affine3d &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1, const std::size_t &id=0) |
Display an arrow along the z-axis of a pose. | |
bool | publishZArrow (const geometry_msgs::Pose &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1) |
bool | publishZArrow (const geometry_msgs::PoseStamped &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1) |
bool | publishZArrow (const geometry_msgs::PoseStamped &pose, const colors &color=BLUE, const scales &scale=REGULAR, double length=0.1, const std::size_t &id=0) |
void | resetMarkerCounts () |
Reset the id's of all published markers so that they overwrite themselves in the future NOTE you may prefer deleteAllMarkers() | |
RvizVisualTools (const std::string &base_frame, const std::string &marker_topic=RVIZ_MARKER_TOPIC) | |
Constructor. | |
void | setAlpha (double alpha) |
Change the transparency of all markers published. | |
void | setBaseFrame (const std::string &base_frame) |
Change the global base frame Note: this might reset all your current markers. | |
void | setFloorToBaseHeight (double floor_to_base_height) |
Allows an offset between base link and floor where objects are built. Default is zero. | |
void | setGlobalScale (double global_scale) |
Setter for the global scale used for changing size of all markers. | |
void | setLifetime (double lifetime) |
Set the lifetime of markers published to rviz. | |
void | setMarkerTopic (const std::string &topic) |
Set marker array topic. | |
void | setPsychedelicMode (const bool &psychedelic_mode=true) |
Setter for PsychedelicMode. | |
double | slerp (double start, double end, double range, double value) |
Interpolate from [start, end] with value of size steps with current value count. | |
bool | triggerBatchPublish () |
Trigger the publish function to send out all collected markers. | |
bool | triggerBatchPublishAndDisable () |
Trigger the publish function to send out all collected markers. Also then turns off the batch mode. This is safer incase programmer forgets. | |
void | waitForMarkerPub () |
Optional blocking function to call *after* calling loadMarkerPub(). Allows you to do some intermediate processing before wasting cycles waiting for the marker pub to find a subscriber. | |
bool | waitForSubscriber (const ros::Publisher &pub, const double &wait_time=0.5, const bool blocking=false) |
Wait until at least one subscriber connects to a publisher. | |
~RvizVisualTools () | |
Deconstructor. | |
Static Public Member Functions | |
static Eigen::Affine3d | convertFromXYZRPY (const double &x, const double &y, const double &z, const double &roll, const double &pitch, const double &yaw) |
Convert a 6-vector of x,y,z, roll,pitch,yall to an Affine3d with quaternion using Euler R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard. | |
static Eigen::Affine3d | convertFromXYZRPY (std::vector< double > transform6) |
static void | convertPoseSafe (const Eigen::Affine3d &pose, geometry_msgs::Pose &pose_msg) |
Convert an Eigen pose to a geometry_msg pose - thread safe. | |
static void | convertToXYZRPY (const Eigen::Affine3d &pose, std::vector< double > &xyzrpy) |
Convert an affine3d to xyz rpy components R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard. | |
static void | convertToXYZRPY (const Eigen::Affine3d &pose, double &x, double &y, double &z, double &roll, double &pitch, double &yaw) |
static double | dRand (double min, double max) |
Get random between min and max. | |
static float | fRand (float min, float max) |
static int | iRand (int min, int max) |
static void | printTransform (const Eigen::Affine3d &transform) |
Display in the console a transform in quaternions. | |
static void | printTransformRPY (const Eigen::Affine3d &transform) |
Display in the console a transform in roll pitch yaw. | |
Protected Member Functions | |
void | enableInternalBatchPublishing (bool enable) |
Allows certain marker functions to batch publish without breaking external functinality. | |
bool | triggerInternalBatchPublishAndDisable () |
Trigger the publish function to send out all collected markers. Also then turns off the batch mode. This is safer incase programmer forgets. This is the internal version. | |
Protected Attributes | |
double | alpha_ |
visualization_msgs::Marker | arrow_marker_ |
std::string | base_frame_ |
bool | batch_publishing_enabled_ |
visualization_msgs::Marker | block_marker_ |
visualization_msgs::Marker | cuboid_marker_ |
visualization_msgs::Marker | cylinder_marker_ |
double | global_scale_ |
bool | internal_batch_publishing_enabled_ |
visualization_msgs::Marker | line_list_marker_ |
visualization_msgs::Marker | line_strip_marker_ |
ros::Duration | marker_lifetime_ |
std::string | marker_topic_ |
visualization_msgs::MarkerArray | markers_ |
visualization_msgs::Marker | mesh_marker_ |
std::string | name_ |
ros::NodeHandle | nh_ |
bool | psychedelic_mode_ |
ros::Publisher | pub_rviz_markers_ |
bool | pub_rviz_markers_connected_ |
bool | pub_rviz_markers_waited_ |
visualization_msgs::Marker | reset_marker_ |
geometry_msgs::Point32 | shared_point32_msg_ |
Eigen::Vector3d | shared_point_eigen_ |
geometry_msgs::Point | shared_point_msg_ |
Eigen::Affine3d | shared_pose_eigen_ |
geometry_msgs::Pose | shared_pose_msg_ |
visualization_msgs::Marker | sphere_marker_ |
visualization_msgs::Marker | spheres_marker_ |
visualization_msgs::Marker | text_marker_ |
visualization_msgs::Marker | triangle_marker_ |
Private Member Functions | |
void | initialize () |
Shared function for initilization by constructors. |
Definition at line 162 of file rviz_visual_tools.h.
rviz_visual_tools::RvizVisualTools::RvizVisualTools | ( | const std::string & | base_frame, |
const std::string & | marker_topic = RVIZ_MARKER_TOPIC |
||
) | [explicit] |
Constructor.
base_frame | - common base for all visualization markers, usually "/world" or "/odom" |
marker_topic | - rostopic to publish markers to - your Rviz display should match |
Definition at line 54 of file rviz_visual_tools.cpp.
rviz_visual_tools::RvizVisualTools::~RvizVisualTools | ( | ) | [inline] |
Deconstructor.
Definition at line 180 of file rviz_visual_tools.h.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::convertFromXYZRPY | ( | const double & | x, |
const double & | y, | ||
const double & | z, | ||
const double & | roll, | ||
const double & | pitch, | ||
const double & | yaw | ||
) | [static] |
Convert a 6-vector of x,y,z, roll,pitch,yall to an Affine3d with quaternion using Euler R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard.
Definition at line 2136 of file rviz_visual_tools.cpp.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::convertFromXYZRPY | ( | std::vector< double > | transform6 | ) | [static] |
Definition at line 2124 of file rviz_visual_tools.cpp.
Eigen::Vector3d rviz_visual_tools::RvizVisualTools::convertPoint | ( | const geometry_msgs::Point & | point | ) |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.
point |
Definition at line 2084 of file rviz_visual_tools.cpp.
geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoint | ( | const geometry_msgs::Vector3 & | point | ) |
Convert a Vector3 to a geometry_msg Point Note: Not thread safe but very convenient.
point |
Definition at line 2108 of file rviz_visual_tools.cpp.
geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoint | ( | const Eigen::Vector3d & | point | ) |
Convert a Eigen point to a geometry_msg Point Note: Not thread safe but very convenient.
point |
Definition at line 2116 of file rviz_visual_tools.cpp.
Eigen::Vector3d rviz_visual_tools::RvizVisualTools::convertPoint32 | ( | const geometry_msgs::Point32 & | point | ) |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.
point |
Definition at line 2092 of file rviz_visual_tools.cpp.
geometry_msgs::Point32 rviz_visual_tools::RvizVisualTools::convertPoint32 | ( | const Eigen::Vector3d & | point | ) |
Convert an Eigen point to a 32 bit geometry_msg point Note: Not thread safe but very convenient.
point |
Definition at line 2100 of file rviz_visual_tools.cpp.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::convertPoint32ToPose | ( | const geometry_msgs::Point32 & | point | ) |
Convert a geometry_msg point (32bit) to an Eigen pose Note: Not thread safe but very convenient.
pose |
Definition at line 2052 of file rviz_visual_tools.cpp.
geometry_msgs::Pose rviz_visual_tools::RvizVisualTools::convertPointToPose | ( | const geometry_msgs::Point & | point | ) |
Add an identity rotation matrix to make a point have a full pose.
Definition at line 2061 of file rviz_visual_tools.cpp.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::convertPointToPose | ( | const Eigen::Vector3d & | point | ) |
Definition at line 2071 of file rviz_visual_tools.cpp.
geometry_msgs::Pose rviz_visual_tools::RvizVisualTools::convertPose | ( | const Eigen::Affine3d & | pose | ) |
Convert an Eigen pose to a geometry_msg pose Note: Not thread safe but very convenient.
pose |
Definition at line 2035 of file rviz_visual_tools.cpp.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::convertPose | ( | const geometry_msgs::Pose & | pose | ) |
Convert a geometry_msg pose to an Eigen pose Note: Not thread safe but very convenient.
pose |
Definition at line 2046 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::convertPoseSafe | ( | const Eigen::Affine3d & | pose, |
geometry_msgs::Pose & | pose_msg | ||
) | [static] |
Convert an Eigen pose to a geometry_msg pose - thread safe.
input | pose |
output | converted pose |
Definition at line 2041 of file rviz_visual_tools.cpp.
geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoseToPoint | ( | const Eigen::Affine3d & | pose | ) |
Convert an Eigen pose to a geometry_msg point Note: Not thread safe but very convenient.
pose |
Definition at line 2078 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::convertToXYZRPY | ( | const Eigen::Affine3d & | pose, |
std::vector< double > & | xyzrpy | ||
) | [static] |
Convert an affine3d to xyz rpy components R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard.
input | Eigen pose |
output | vector of size 6 in order xyz rpy |
Definition at line 2148 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::convertToXYZRPY | ( | const Eigen::Affine3d & | pose, |
double & | x, | ||
double & | y, | ||
double & | z, | ||
double & | roll, | ||
double & | pitch, | ||
double & | yaw | ||
) | [static] |
Definition at line 2154 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::createRandColor | ( | ) |
Create a random color that is not too light.
Definition at line 504 of file rviz_visual_tools.cpp.
Tell Rviz to clear all markers on a particular display. Note: only works on ROS Indigo and newer.
Definition at line 77 of file rviz_visual_tools.cpp.
double rviz_visual_tools::RvizVisualTools::dRand | ( | double | min, |
double | max | ||
) | [static] |
Get random between min and max.
Definition at line 2264 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::enableBatchPublishing | ( | bool | enable = true | ) |
Enable batch publishing - useful for when many markers need to be published at once and the ROS topic can get overloaded. This collects all published markers into array and only publishes them with triggerBatchPublish() is called.
Definition at line 710 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::enableInternalBatchPublishing | ( | bool | enable | ) | [protected] |
Allows certain marker functions to batch publish without breaking external functinality.
Definition at line 2288 of file rviz_visual_tools.cpp.
float rviz_visual_tools::RvizVisualTools::fRand | ( | float | min, |
float | max | ||
) | [static] |
Definition at line 2270 of file rviz_visual_tools.cpp.
Create a pose of position (0,0,0) and quaternion (0,0,0,1)
Pose | to fill in |
Definition at line 2235 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::generateRandomCuboid | ( | geometry_msgs::Pose & | cuboid_pose, |
double & | depth, | ||
double & | width, | ||
double & | height, | ||
RandomPoseBounds | pose_bounds = RandomPoseBounds() , |
||
RandomCuboidBounds | cuboid_bounds = RandomCuboidBounds() |
||
) |
Create a random rectangular cuboid of some shape.
Definition at line 2174 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::generateRandomPose | ( | geometry_msgs::Pose & | pose, |
RandomPoseBounds | pose_bounds = RandomPoseBounds() |
||
) |
Create a random pose within bounds of random_pose_bounds_.
Pose | to fill in options bounds on the pose to generate |
Definition at line 2168 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::generateRandomPose | ( | Eigen::Affine3d & | pose, |
RandomPoseBounds | pose_bounds = RandomPoseBounds() |
||
) |
Definition at line 2187 of file rviz_visual_tools.cpp.
const std::string rviz_visual_tools::RvizVisualTools::getBaseFrame | ( | ) | [inline] |
Eigen::Vector3d rviz_visual_tools::RvizVisualTools::getCenterPoint | ( | Eigen::Vector3d | a, |
Eigen::Vector3d | b | ||
) |
Find the center between to points.
point | a - x,y,z in space of a point |
point | b - x,y,z in space of a point |
Definition at line 638 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColor | ( | const colors & | color | ) |
Get the RGB value of standard colors.
color | - an enum pre-defined name of a color |
Definition at line 373 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColorScale | ( | double | value | ) |
Convert a value from [0,1] to a color Green->Red.
Definition at line 539 of file rviz_visual_tools.cpp.
double rviz_visual_tools::RvizVisualTools::getGlobalScale | ( | ) | [inline] |
Getter for the global scale used for changing size of all markers.
Definition at line 327 of file rviz_visual_tools.h.
const bool& rviz_visual_tools::RvizVisualTools::getPsychedelicMode | ( | ) | const [inline] |
Getter for PsychedelicMode.
Definition at line 916 of file rviz_visual_tools.h.
Get a random color from the list of hardcoded enum color types.
Definition at line 349 of file rviz_visual_tools.cpp.
geometry_msgs::Vector3 rviz_visual_tools::RvizVisualTools::getScale | ( | const scales & | scale, |
bool | arrow_scale = false , |
||
double | marker_scale = 1.0 |
||
) |
Get the rviz marker scale of standard sizes.
scale | - an enum pre-defined name of a size |
arrow_scale | - they do not have an even scaling, compensate |
marker_scale | - amount to scale the scale for accounting for different types of markers |
Definition at line 582 of file rviz_visual_tools.cpp.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::getVectorBetweenPoints | ( | Eigen::Vector3d | a, |
Eigen::Vector3d | b | ||
) |
Create a vector that points from point a to point b.
point | a - x,y,z in space of a point |
point | b - x,y,z in space of a point |
Definition at line 647 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::initialize | ( | ) | [private] |
Shared function for initilization by constructors.
Definition at line 68 of file rviz_visual_tools.cpp.
int rviz_visual_tools::RvizVisualTools::iRand | ( | int | min, |
int | max | ||
) | [static] |
Definition at line 2276 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::loadMarkerPub | ( | bool | wait_for_subscriber = false , |
bool | latched = false |
||
) |
Load publishers as needed.
wait_for_subscriber | - whether a sleep for loop should be used to check for connectivity to an external node before proceeding |
Definition at line 268 of file rviz_visual_tools.cpp.
Pre-load rviz markers for better efficiency.
Definition at line 98 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::posesEqual | ( | const Eigen::Affine3d & | pose1, |
const Eigen::Affine3d & | pose2, | ||
const double & | threshold = 0.000001 |
||
) |
Test if two Eigen poses are close enough.
pose1 | |
pose2 | |
threshold | - how close in value they must be in order to be considered the same |
Definition at line 2249 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::printTransform | ( | const Eigen::Affine3d & | transform | ) | [static] |
Display in the console a transform in quaternions.
Definition at line 2308 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::printTransformRPY | ( | const Eigen::Affine3d & | transform | ) | [static] |
Display in the console a transform in roll pitch yaw.
Definition at line 2316 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishArrow | ( | const Eigen::Affine3d & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 , |
||
const std::size_t & | id = 0 |
||
) |
Display an arrow along the x-axis of a pose.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
length | - how long the arrow tail should be |
Definition at line 1130 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishArrow | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1136 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishArrow | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1157 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishAxis | ( | const geometry_msgs::Pose & | pose, |
double | length = 0.1 , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Axis" |
||
) |
Display a marker of a axis.
pose | - the location to publish the marker with respect to the base frame |
length | - geometry of cylinder |
radius | - geometry of cylinder |
Definition at line 1221 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishAxis | ( | const Eigen::Affine3d & | pose, |
double | length = 0.1 , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Axis" |
||
) |
Definition at line 1226 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishAxisLabeled | ( | const Eigen::Affine3d & | pose, |
const std::string & | label, | ||
const scales & | scale = SMALL , |
||
const colors & | color = WHITE |
||
) |
Display a marker of a axis with a text label describing it.
pose | - the location to publish the marker with respect to the base frame |
label | - name of axis/coordinate frame |
scale | - size of axis |
color | - an enum pre-defined name of a color |
Definition at line 1206 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishAxisLabeled | ( | const geometry_msgs::Pose & | pose, |
const std::string & | label, | ||
const scales & | scale = SMALL , |
||
const colors & | color = WHITE |
||
) |
Definition at line 1211 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishBlock | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = BLUE , |
||
const double & | block_size = 0.1 |
||
) |
Display a marker of a block.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
size | - height=width=depth=size |
Definition at line 1179 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishBlock | ( | const Eigen::Affine3d & | pose, |
const colors & | color = BLUE , |
||
const double & | block_size = 0.1 |
||
) |
Definition at line 1201 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCone | ( | const Eigen::Affine3d & | pose, |
double | angle, | ||
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Display a cone of a given angle along the x-axis.
pose | - the location and orientation of the cone |
color | - color of the cone |
scale | - size of the cone |
Definition at line 771 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCone | ( | const geometry_msgs::Pose & | pose, |
double | angle, | ||
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Definition at line 776 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const colors & | color = BLUE |
||
) |
Display a rectangular cuboid.
point1 | - x,y,z top corner location of box |
point2 | - x,y,z bottom opposite corner location of box |
color | - an enum pre-defined name of a color |
Definition at line 1387 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const geometry_msgs::Point & | point1, |
const geometry_msgs::Point & | point2, | ||
const colors & | color = BLUE , |
||
const std::string & | ns = "Cuboid" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1392 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const geometry_msgs::Pose & | pose, |
const double | depth, | ||
const double | width, | ||
const double | height, | ||
const colors & | color = BLUE |
||
) |
Display a rectangular cuboid.
pose | - pose of the box |
depth | - depth of the box |
width | - width of the box |
height | - height of the box |
color | - an enum pre-defined name of a color |
Definition at line 1436 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const Eigen::Affine3d & | pose, |
const double | depth, | ||
const double | width, | ||
const double | height, | ||
const colors & | color = BLUE |
||
) |
Definition at line 1430 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCylinder | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const colors & | color = BLUE , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Cylinder" |
||
) |
Display a marker of a cylinder.
point1 | - starting side of cylinder |
point2 | - end side of cylinder |
color | - an enum pre-defined name of a color |
radius | - geometry of cylinder |
Definition at line 1252 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCylinder | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const std_msgs::ColorRGBA & | color, | ||
double | radius = 0.01 , |
||
const std::string & | ns = "Cylinder" |
||
) |
Definition at line 1258 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCylinder | ( | const Eigen::Affine3d & | pose, |
const colors & | color = BLUE , |
||
double | height = 0.1 , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Cylinder" |
||
) |
Display a marker of a cylinder.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
height | - geometry of cylinder |
radius | - geometry of cylinder |
Definition at line 1280 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCylinder | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = BLUE , |
||
double | height = 0.1 , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Cylinder" |
||
) |
Definition at line 1286 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishCylinder | ( | const geometry_msgs::Pose & | pose, |
const std_msgs::ColorRGBA & | color, | ||
double | height = 0.1 , |
||
double | radius = 0.01 , |
||
const std::string & | ns = "Cylinder" |
||
) |
Definition at line 1292 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishGraph | ( | const graph_msgs::GeometryGraph & | graph, |
const colors & | color, | ||
double | radius | ||
) |
Display a graph.
graph | of nodes and edges |
color | - an enum pre-defined name of a color |
radius | - width of cylinders |
Definition at line 1355 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const Eigen::Affine3d & | point1, |
const Eigen::Affine3d & | point2, | ||
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR |
||
) |
Display a marker of line.
point1 | - x,y,z of start of line |
point2 | - x,y,z of end of line |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
Definition at line 1465 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR |
||
) |
Definition at line 1471 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const colors & | color, | ||
const double & | radius | ||
) |
Definition at line 1476 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const std_msgs::ColorRGBA & | color, | ||
const scales & | scale = REGULAR |
||
) |
Definition at line 1486 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const std_msgs::ColorRGBA & | color, | ||
const double & | radius | ||
) |
Definition at line 1492 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const geometry_msgs::Point & | point1, |
const geometry_msgs::Point & | point2, | ||
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR |
||
) |
Definition at line 1502 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const geometry_msgs::Point & | point1, |
const geometry_msgs::Point & | point2, | ||
const std_msgs::ColorRGBA & | color, | ||
const scales & | scale = REGULAR |
||
) |
Definition at line 1508 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishLine | ( | const geometry_msgs::Point & | point1, |
const geometry_msgs::Point & | point2, | ||
const std_msgs::ColorRGBA & | color, | ||
const geometry_msgs::Vector3 & | scale | ||
) |
Definition at line 1514 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishMarker | ( | visualization_msgs::Marker & | marker | ) |
Display a visualization_msgs Marker of a custom type. Allows reuse of the ros publisher.
marker | - a pre-made marker ready to be published |
Definition at line 696 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishMarkers | ( | visualization_msgs::MarkerArray & | markers | ) |
Display an array of markers, allows reuse of the ROS publisher.
markers |
Definition at line 729 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishMesh | ( | const Eigen::Affine3d & | pose, |
const std::string & | file_name, | ||
const colors & | color = CLEAR , |
||
double | scale = 1 , |
||
const std::string & | ns = "mesh" , |
||
const std::size_t & | id = 0 |
||
) |
Display a mesh from file.
pose | - the location to publish the marker with respect to the base frame |
file | name of mesh, starting with "file://" e.g. "file:///home/user/mesh.stl" |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
ns | - namespace of marker |
id | - unique counter of mesh that allows you to overwrite a previous mesh. if 0, defaults to incremental counter |
Definition at line 1315 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishMesh | ( | const geometry_msgs::Pose & | pose, |
const std::string & | file_name, | ||
const colors & | color = CLEAR , |
||
double | scale = 1 , |
||
const std::string & | ns = "mesh" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1321 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishPath | ( | const std::vector< geometry_msgs::Point > & | path, |
const colors & | color = RED , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Path" |
||
) |
Display a marker of a series of connected lines.
path | - a series of points to connect with lines |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
ns | - namespace of marker |
Definition at line 1532 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishPath | ( | const std::vector< Eigen::Vector3d > & | path, |
const colors & | color = RED , |
||
const double | radius = 0.01 , |
||
const std::string & | ns = "Path" |
||
) |
Definition at line 1566 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishPolygon | ( | const geometry_msgs::Polygon & | polygon, |
const colors & | color = RED , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Polygon" |
||
) |
Display a marker of a polygon.
polygon | - a series of points to connect with lines |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
ns | - namespace of marker |
Definition at line 1588 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const Eigen::Affine3d & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Display a marker of a sphere.
pose | - the location to publish the sphere with respect to the base frame |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
ns | - namespace of marker |
id | - unique counter of mesh that allows you to overwrite a previous mesh. if 0, defaults to incremental counter |
Definition at line 955 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const Eigen::Vector3d & | point, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 961 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const Eigen::Vector3d & | point, |
const colors & | color, | ||
const double | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 969 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::Point & | point, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 977 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 985 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::Pose & | pose, |
const colors & | color, | ||
const double | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 991 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::Pose & | pose, |
const colors & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1001 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::Pose & | pose, |
const std_msgs::ColorRGBA & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1013 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const Eigen::Affine3d & | pose, |
const std_msgs::ColorRGBA & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1007 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSphere | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
const std::string & | ns = "Sphere" , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1034 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSpheres | ( | const std::vector< Eigen::Vector3d > & | points, |
const colors & | color = BLUE , |
||
const double | scale = 0.1 , |
||
const std::string & | ns = "Spheres" |
||
) |
Display a marker of a series of spheres.
spheres | - where to publish them |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
ns | - namespace of marker |
Definition at line 1829 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSpheres | ( | const std::vector< geometry_msgs::Point > & | points, |
const colors & | color = BLUE , |
||
const double | scale = 0.1 , |
||
const std::string & | ns = "Spheres" |
||
) |
Definition at line 1844 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSpheres | ( | const std::vector< geometry_msgs::Point > & | points, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::string & | ns = "Spheres" |
||
) |
Definition at line 1854 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishSpheres | ( | const std::vector< geometry_msgs::Point > & | points, |
const colors & | color, | ||
const geometry_msgs::Vector3 & | scale, | ||
const std::string & | ns = "Spheres" |
||
) |
Definition at line 1860 of file rviz_visual_tools.cpp.
Run a simple test of all visual_tool's features.
Definition at line 1935 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishText | ( | const Eigen::Affine3d & | pose, |
const std::string & | text, | ||
const colors & | color = WHITE , |
||
const scales & | scale = REGULAR , |
||
bool | static_id = true |
||
) |
Display a marker of a text.
pose | - the location to publish the marker with respect to the base frame |
text | - what message to display |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
static_id | - if true, only one text can be published at a time |
Definition at line 1886 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishText | ( | const Eigen::Affine3d & | pose, |
const std::string & | text, | ||
const colors & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
bool | static_id = true |
||
) |
Definition at line 1892 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishText | ( | const geometry_msgs::Pose & | pose, |
const std::string & | text, | ||
const colors & | color = WHITE , |
||
const scales & | scale = REGULAR , |
||
bool | static_id = true |
||
) |
Definition at line 1898 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishText | ( | const geometry_msgs::Pose & | pose, |
const std::string & | text, | ||
const colors & | color, | ||
const geometry_msgs::Vector3 | scale, | ||
bool | static_id = true |
||
) |
Definition at line 1904 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishWireframeCuboid | ( | const Eigen::Affine3d & | pose, |
double | depth, | ||
double | width, | ||
double | height, | ||
const rviz_visual_tools::colors & | color = BLUE , |
||
const std::string & | ns = "Wireframe Cuboid" , |
||
const std::size_t & | id = 0 |
||
) |
Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box.
pose | - cuboid vertices are transformed according to it |
depth | - object depth |
width | - object width |
height | - object height |
color | - an enum pre-defined name of a color |
ns | - namespace |
id | - unique counter of mesh that allows you to overwrite a previous mesh. if 0, defaults to incremental counter |
Definition at line 1610 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishWireframeCuboid | ( | const Eigen::Affine3d & | pose, |
const Eigen::Vector3d & | min_point, | ||
const Eigen::Vector3d & | max_point, | ||
const rviz_visual_tools::colors & | color = BLUE , |
||
const std::string & | ns = "Wireframe Cuboid" , |
||
const std::size_t & | id = 0 |
||
) |
Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box.
pose | - cuboid vertices are transformed according to it |
min_point | - minimum x, y, z coordinates |
max_point | - maximum x, y, z coordinates |
color | - an enum pre-defined name of a color |
ns | - namespace |
id | - unique counter that allows you to overwrite a previous marker. if 0, defaults to incremental counter |
Definition at line 1619 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishWireframeRectangle | ( | const Eigen::Affine3d & | pose, |
const double & | height, | ||
const double & | width, | ||
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
const std::size_t & | id = 0 |
||
) |
Publish outline of a rectangle.
pose | - cuboid vertices are transformed according to it |
height | |
width | |
color | - an enum pre-defined name of a color |
id | - unique counter that allows you to overwrite a previous marker. if 0, defaults to incremental counter |
Definition at line 1722 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishWireframeRectangle | ( | const Eigen::Affine3d & | pose, |
const Eigen::Vector3d & | p1, | ||
const Eigen::Vector3d & | p2, | ||
const Eigen::Vector3d & | p3, | ||
const Eigen::Vector3d & | p4, | ||
const colors & | color, | ||
const scales & | scale | ||
) |
Definition at line 1776 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXArrow | ( | const Eigen::Affine3d & | pose, |
const colors & | color = RED , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Display an arrow along the x-axis of a pose.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
length | - the length of the arrow tail |
Definition at line 1057 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXArrow | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = RED , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1063 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXArrow | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color = RED , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1069 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXYPlane | ( | const Eigen::Affine3d & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Display the XY plane of a given pose.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 817 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXYPlane | ( | const geometry_msgs::Pose & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Definition at line 822 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXZPlane | ( | const Eigen::Affine3d & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Display the XY plane of a given pose.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 863 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishXZPlane | ( | const geometry_msgs::Pose & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Definition at line 868 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishYArrow | ( | const Eigen::Affine3d & | pose, |
const colors & | color = GREEN , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Display an arrow along the y-axis of a pose.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
length | - the length of the arrow tail |
Definition at line 1075 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishYArrow | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = GREEN , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1082 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishYArrow | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color = GREEN , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1089 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishYZPlane | ( | const Eigen::Affine3d & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Display the XY plane of a given pose.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 909 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishYZPlane | ( | const geometry_msgs::Pose & | pose, |
const rviz_visual_tools::colors & | color = TRANSLUCENT , |
||
double | scale = 1.0 |
||
) |
Definition at line 914 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishZArrow | ( | const Eigen::Affine3d & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 , |
||
const std::size_t & | id = 0 |
||
) |
Display an arrow along the z-axis of a pose.
pose | - the location to publish the marker with respect to the base frame |
color | - an enum pre-defined name of a color |
scale | - an enum pre-defined name of a size |
length | - the length of the arrow tail |
Definition at line 1098 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishZArrow | ( | const geometry_msgs::Pose & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1105 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishZArrow | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 |
||
) |
Definition at line 1112 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::publishZArrow | ( | const geometry_msgs::PoseStamped & | pose, |
const colors & | color = BLUE , |
||
const scales & | scale = REGULAR , |
||
double | length = 0.1 , |
||
const std::size_t & | id = 0 |
||
) |
Definition at line 1121 of file rviz_visual_tools.cpp.
Reset the id's of all published markers so that they overwrite themselves in the future NOTE you may prefer deleteAllMarkers()
Definition at line 83 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::setAlpha | ( | double | alpha | ) | [inline] |
Change the transparency of all markers published.
alpha | - value 0 - 1 where 0 is invisible |
Definition at line 239 of file rviz_visual_tools.h.
void rviz_visual_tools::RvizVisualTools::setBaseFrame | ( | const std::string & | base_frame | ) | [inline] |
Change the global base frame Note: this might reset all your current markers.
name | of frame |
Definition at line 318 of file rviz_visual_tools.h.
void rviz_visual_tools::RvizVisualTools::setFloorToBaseHeight | ( | double | floor_to_base_height | ) |
Allows an offset between base link and floor where objects are built. Default is zero.
floor_to_base_height | - the offset |
Definition at line 329 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::setGlobalScale | ( | double | global_scale | ) | [inline] |
Setter for the global scale used for changing size of all markers.
Definition at line 334 of file rviz_visual_tools.h.
void rviz_visual_tools::RvizVisualTools::setLifetime | ( | double | lifetime | ) |
Set the lifetime of markers published to rviz.
lifetime | seconds of how long to show markers. 0 for inifinity |
Definition at line 334 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::setMarkerTopic | ( | const std::string & | topic | ) | [inline] |
Set marker array topic.
Definition at line 203 of file rviz_visual_tools.h.
void rviz_visual_tools::RvizVisualTools::setPsychedelicMode | ( | const bool & | psychedelic_mode = true | ) | [inline] |
Setter for PsychedelicMode.
Definition at line 922 of file rviz_visual_tools.h.
double rviz_visual_tools::RvizVisualTools::slerp | ( | double | start, |
double | end, | ||
double | range, | ||
double | value | ||
) |
Interpolate from [start, end] with value of size steps with current value count.
Definition at line 533 of file rviz_visual_tools.cpp.
Trigger the publish function to send out all collected markers.
Definition at line 715 of file rviz_visual_tools.cpp.
Trigger the publish function to send out all collected markers. Also then turns off the batch mode. This is safer incase programmer forgets.
Definition at line 723 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::triggerInternalBatchPublishAndDisable | ( | ) | [protected] |
Trigger the publish function to send out all collected markers. Also then turns off the batch mode. This is safer incase programmer forgets. This is the internal version.
Definition at line 2298 of file rviz_visual_tools.cpp.
Optional blocking function to call *after* calling loadMarkerPub(). Allows you to do some intermediate processing before wasting cycles waiting for the marker pub to find a subscriber.
Definition at line 281 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::waitForSubscriber | ( | const ros::Publisher & | pub, |
const double & | wait_time = 0.5 , |
||
const bool | blocking = false |
||
) |
Wait until at least one subscriber connects to a publisher.
pub | - the publisher to check for subscribers |
wait_time | - time to wait for subscriber to be available before throwing warning |
blocking | - if true, the function loop until a subscriber is gotten |
Definition at line 287 of file rviz_visual_tools.cpp.
double rviz_visual_tools::RvizVisualTools::alpha_ [protected] |
Definition at line 963 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::arrow_marker_ [protected] |
Definition at line 970 of file rviz_visual_tools.h.
std::string rviz_visual_tools::RvizVisualTools::base_frame_ [protected] |
Definition at line 954 of file rviz_visual_tools.h.
bool rviz_visual_tools::RvizVisualTools::batch_publishing_enabled_ [protected] |
Definition at line 960 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::block_marker_ [protected] |
Definition at line 972 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::cuboid_marker_ [protected] |
Definition at line 976 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::cylinder_marker_ [protected] |
Definition at line 973 of file rviz_visual_tools.h.
double rviz_visual_tools::RvizVisualTools::global_scale_ [protected] |
Definition at line 964 of file rviz_visual_tools.h.
Definition at line 961 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::line_list_marker_ [protected] |
Definition at line 978 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::line_strip_marker_ [protected] |
Definition at line 977 of file rviz_visual_tools.h.
Definition at line 957 of file rviz_visual_tools.h.
std::string rviz_visual_tools::RvizVisualTools::marker_topic_ [protected] |
Definition at line 953 of file rviz_visual_tools.h.
visualization_msgs::MarkerArray rviz_visual_tools::RvizVisualTools::markers_ [protected] |
Definition at line 967 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::mesh_marker_ [protected] |
Definition at line 974 of file rviz_visual_tools.h.
std::string rviz_visual_tools::RvizVisualTools::name_ [protected] |
Definition at line 945 of file rviz_visual_tools.h.
Definition at line 942 of file rviz_visual_tools.h.
bool rviz_visual_tools::RvizVisualTools::psychedelic_mode_ [protected] |
Definition at line 991 of file rviz_visual_tools.h.
Definition at line 948 of file rviz_visual_tools.h.
bool rviz_visual_tools::RvizVisualTools::pub_rviz_markers_connected_ [protected] |
Definition at line 949 of file rviz_visual_tools.h.
bool rviz_visual_tools::RvizVisualTools::pub_rviz_markers_waited_ [protected] |
Definition at line 950 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::reset_marker_ [protected] |
Definition at line 980 of file rviz_visual_tools.h.
geometry_msgs::Point32 rviz_visual_tools::RvizVisualTools::shared_point32_msg_ [protected] |
Definition at line 986 of file rviz_visual_tools.h.
Eigen::Vector3d rviz_visual_tools::RvizVisualTools::shared_point_eigen_ [protected] |
Definition at line 988 of file rviz_visual_tools.h.
Definition at line 985 of file rviz_visual_tools.h.
Eigen::Affine3d rviz_visual_tools::RvizVisualTools::shared_pose_eigen_ [protected] |
Definition at line 987 of file rviz_visual_tools.h.
Definition at line 984 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::sphere_marker_ [protected] |
Definition at line 971 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::spheres_marker_ [protected] |
Definition at line 979 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::text_marker_ [protected] |
Definition at line 975 of file rviz_visual_tools.h.
visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::triangle_marker_ [protected] |
Definition at line 981 of file rviz_visual_tools.h.