Public Member Functions | Static Public Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions | List of all members
rviz_visual_tools::RvizVisualTools Class Reference

#include <rviz_visual_tools.h>

Public Member Functions

std_msgs::ColorRGBA createRandColor () const
 Create a random color that is not too light. More...
 
bool deleteAllMarkers ()
 Tell Rviz to clear all markers on a particular display. More...
 
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 trigger() is called. More...
 
void enableFrameLocking (bool enable=true)
 Enable frame locking - useful for when the markers is attached to a moving TF, the marker will be re-transformed into its frame every time-step. More...
 
const std::string getBaseFrame () const
 Get the base frame. More...
 
Eigen::Vector3d getCenterPoint (const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
 Find the center between to points. More...
 
std_msgs::ColorRGBA getColor (colors color) const
 Get the RGB value of standard colors. More...
 
std_msgs::ColorRGBA getColorScale (double value) const
 Convert a value from [0,1] to a color Green->Red. More...
 
double getGlobalScale () const
 Getter for the global scale used for changing size of all markers. More...
 
bool getPsychedelicMode () const
 Getter for PsychedelicMode. More...
 
RemoteControlPtrgetRemoteControl ()
 Ability to load remote control on the fly. More...
 
geometry_msgs::Vector3 getScale (scales scale, double marker_scale=1.0) const
 Get the rviz marker scale of standard sizes. More...
 
Eigen::Isometry3d getVectorBetweenPoints (const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
 Create a vector that points from point a to point b. More...
 
void loadMarkerPub (bool wait_for_subscriber=false, bool latched=false)
 Load publishers as needed. More...
 
void loadRemoteControl ()
 Pre-load remote control. More...
 
bool loadRvizMarkers ()
 Pre-load rviz markers for better efficiency. More...
 
void prompt (const std::string &msg)
 Wait for user feedback i.e. through a button or joystick. More...
 
bool publishArrow (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 Display an arrow along the x-axis of a pose. More...
 
bool publishArrow (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishArrow (const geometry_msgs::Point &start, const geometry_msgs::Point &end, colors color=BLUE, scales scale=MEDIUM, std::size_t id=0)
 
bool publishAxis (const geometry_msgs::Pose &pose, scales scale=MEDIUM, const std::string &ns="Axis")
 Display a red/green/blue coordinate frame axis. More...
 
bool publishAxis (const Eigen::Isometry3d &pose, scales scale=MEDIUM, const std::string &ns="Axis")
 
bool publishAxis (const geometry_msgs::Pose &pose, double length, double radius=0.01, const std::string &ns="Axis")
 
bool publishAxis (const Eigen::Isometry3d &pose, double length, double radius=0.01, const std::string &ns="Axis")
 
bool publishAxisLabeled (const Eigen::Isometry3d &pose, const std::string &label, scales scale=MEDIUM, colors color=WHITE)
 Display a marker of a coordinate frame axis with a text label describing it. More...
 
bool publishAxisLabeled (const geometry_msgs::Pose &pose, const std::string &label, scales scale=MEDIUM, colors color=WHITE)
 
bool publishAxisPath (const EigenSTL::vector_Isometry3d &path, scales scale=MEDIUM, const std::string &ns="Axis Path")
 Display a series of red/green/blue coordinate axis along a path. More...
 
bool publishAxisPath (const EigenSTL::vector_Isometry3d &path, double length=0.1, double radius=0.01, const std::string &ns="Axis Path")
 
bool publishCone (const Eigen::Isometry3d &pose, double angle, colors color=TRANSLUCENT, double scale=1.0)
 Display a cone of a given angle along the x-axis. More...
 
bool publishCone (const geometry_msgs::Pose &pose, double angle, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishCuboid (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE)
 Display a rectangular cuboid. More...
 
bool publishCuboid (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, colors color=BLUE, const std::string &ns="Cuboid", std::size_t id=0)
 
bool publishCuboid (const geometry_msgs::Pose &pose, double depth, double width, double height, colors color=BLUE)
 Display a rectangular cuboid. More...
 
bool publishCuboid (const Eigen::Isometry3d &pose, double depth, double width, double height, colors color=BLUE)
 
bool publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Cylinder")
 Display a marker of a cylinder. More...
 
bool publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color, double radius=0.01, const std::string &ns="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::Isometry3d &pose, colors color=BLUE, double height=0.1, double radius=0.01, const std::string &ns="Cylinder")
 Display a marker of a cylinder. More...
 
bool publishCylinder (const geometry_msgs::Pose &pose, 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, colors color, double radius)
 Display a graph. More...
 
bool publishLine (const Eigen::Isometry3d &point1, const Eigen::Isometry3d &point2, colors color=BLUE, scales scale=MEDIUM)
 Display a marker of line. More...
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE, scales scale=MEDIUM)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color, double radius)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, scales scale=MEDIUM)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, double radius)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, colors color=BLUE, scales scale=MEDIUM)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, scales scale=MEDIUM)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 &scale)
 
bool publishLines (const EigenSTL::vector_Vector3d &aPoints, const EigenSTL::vector_Vector3d &bPoints, const std::vector< colors > &colors, scales scale=MEDIUM)
 Display a marker of lines. More...
 
bool publishLines (const std::vector< geometry_msgs::Point > &aPoints, const std::vector< geometry_msgs::Point > &bPoints, const std::vector< std_msgs::ColorRGBA > &colors, const geometry_msgs::Vector3 &scale)
 
bool publishLineStrip (const std::vector< geometry_msgs::Point > &path, colors color=RED, scales scale=MEDIUM, const std::string &ns="Path")
 Display a series of connected lines using the LINE_STRIP method - deprecated because visual bugs. More...
 
bool publishMarker (visualization_msgs::Marker &marker)
 Display a visualization_msgs Marker of a custom type. Allows reuse of the ros publisher. More...
 
bool publishMarkers (visualization_msgs::MarkerArray &markers)
 Display an array of markers, allows reuse of the ROS publisher. More...
 
bool publishMesh (const Eigen::Isometry3d &pose, const std::string &file_name, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 Display a mesh from file. More...
 
bool publishMesh (const geometry_msgs::Pose &pose, const std::string &file_name, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 
bool publishPath (const std::vector< geometry_msgs::Pose > &path, colors color=RED, scales scale=MEDIUM, const std::string &ns="Path")
 Display a marker of a series of connected cylinders. More...
 
bool publishPath (const std::vector< geometry_msgs::Point > &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Isometry3d &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const std::vector< geometry_msgs::Point > &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Isometry3d &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, const std::vector< colors > &colors, double radius=0.01, const std::string &ns="Path")
 Display a marker of a series of connected colored cylinders. More...
 
bool publishPath (const EigenSTL::vector_Vector3d &path, const std::vector< std_msgs::ColorRGBA > &colors, double radius, const std::string &ns="Path")
 
bool publishPolygon (const geometry_msgs::Polygon &polygon, colors color=RED, scales scale=MEDIUM, const std::string &ns="Polygon")
 Display a marker of a polygon. More...
 
bool publishSphere (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 Display a marker of a sphere. More...
 
bool publishSphere (const Eigen::Vector3d &point, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Vector3d &point, colors color, double scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Point &point, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color, double scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", 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", std::size_t id=0)
 
bool publishSphere (const Eigen::Isometry3d &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Vector3d &point, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::PoseStamped &pose, colors color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Spheres")
 Display a marker of a series of spheres. More...
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, colors color, double scale=0.1, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color=BLUE, double scale=0.1, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color, const geometry_msgs::Vector3 &scale, const std::string &ns="Spheres")
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, const std::vector< colors > &colors, scales scale=MEDIUM, const std::string &ns="Spheres")
 Display a marker of a series of spheres, with the possibility of different colors. More...
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, const std::vector< std_msgs::ColorRGBA > &colors, const geometry_msgs::Vector3 &scale, const std::string &ns="Spheres")
 
bool publishText (const Eigen::Isometry3d &pose, const std::string &text, colors color=WHITE, scales scale=MEDIUM, bool static_id=true)
 Display a marker of a text. More...
 
bool publishText (const Eigen::Isometry3d &pose, const std::string &text, colors color, const geometry_msgs::Vector3 scale, bool static_id=true)
 
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, colors color=WHITE, scales scale=MEDIUM, bool static_id=true)
 
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, colors color, const geometry_msgs::Vector3 scale, bool static_id=true)
 
bool publishWireframeCuboid (const Eigen::Isometry3d &pose, double depth, double width, double height, colors color=BLUE, const std::string &ns="Wireframe Cuboid", std::size_t id=0)
 Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box. More...
 
bool publishWireframeCuboid (const Eigen::Isometry3d &pose, const Eigen::Vector3d &min_point, const Eigen::Vector3d &max_point, colors color=BLUE, const std::string &ns="Wireframe Cuboid", std::size_t id=0)
 Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box. More...
 
bool publishWireframeRectangle (const Eigen::Isometry3d &pose, double height, double width, colors color=BLUE, scales scale=MEDIUM, std::size_t id=0)
 Publish outline of a rectangle. More...
 
bool publishWireframeRectangle (const Eigen::Isometry3d &pose, const Eigen::Vector3d &p1_in, const Eigen::Vector3d &p2_in, const Eigen::Vector3d &p3_in, const Eigen::Vector3d &p4_in, colors color, scales scale)
 
bool publishXArrow (const Eigen::Isometry3d &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 Display an arrow along the x-axis of a pose. More...
 
bool publishXArrow (const geometry_msgs::Pose &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 
bool publishXArrow (const geometry_msgs::PoseStamped &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 
bool publishXYPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 Display the XY plane of a given pose. More...
 
bool publishXYPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishXZPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 Display the XY plane of a given pose. More...
 
bool publishXZPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishYArrow (const Eigen::Isometry3d &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 Display an arrow along the y-axis of a pose. More...
 
bool publishYArrow (const geometry_msgs::Pose &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 
bool publishYArrow (const geometry_msgs::PoseStamped &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 
bool publishYZPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 Display the XY plane of a given pose. More...
 
bool publishYZPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishZArrow (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 Display an arrow along the z-axis of a pose. More...
 
bool publishZArrow (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0)
 
bool publishZArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0)
 
bool publishZArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, 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() More...
 
 RvizVisualTools (std::string base_frame, std::string marker_topic=RVIZ_MARKER_TOPIC, ros::NodeHandle nh=ros::NodeHandle("~"))
 Constructor. More...
 
void setAlpha (double alpha)
 Change the transparency of all markers published. More...
 
void setBaseFrame (const std::string &base_frame)
 Change the global base frame Note: this might reset all your current markers. More...
 
void setGlobalScale (double global_scale)
 Setter for the global scale used for changing size of all markers. More...
 
void setLifetime (double lifetime)
 Set the lifetime of markers published to rviz. More...
 
void setMarkerTopic (const std::string &topic)
 Set marker array topic. More...
 
void setPsychedelicMode (bool psychedelic_mode=true)
 Setter for PsychedelicMode. More...
 
bool trigger ()
 Trigger the publish function to send out all collected markers. More...
 
bool triggerEvery (std::size_t queueSize)
 Trigger the publish function to send out all collected markers IF there are at leats queueSize number of markers ready to be published. a * Warning: when using this in a loop be sure to call trigger() at end of loop in case there are any remainder markers in the queue. More...
 
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. More...
 
void waitForMarkerPub (double wait_time)
 
bool waitForSubscriber (const ros::Publisher &pub, double wait_time=0.5, bool blocking=false)
 Wait until at least one subscriber connects to a publisher. More...
 
 ~RvizVisualTools ()
 Deconstructor. More...
 

Static Public Member Functions

static Eigen::Isometry3d convertFromXYZRPY (double tx, double ty, double tz, double rx, double ry, double rz, EulerConvention convention)
 Converts scalar translations and rotations to an Eigen Frame. This is achieved by chaining a translation with individual euler rotations in ZYX order (this is equivalent to fixed rotatins XYZ) http://en.wikipedia.org/wiki/Euler_angles#Conversion_between_intrinsic_and_extrinsic_rotations Euler conversion code sourced from Descartes, Copyright (c) 2014, Southwest Research Institute. More...
 
static Eigen::Isometry3d convertFromXYZRPY (const std::vector< double > &transform6, EulerConvention convention)
 
static Eigen::Vector3d convertPoint (const geometry_msgs::Point &point)
 Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient. More...
 
static geometry_msgs::Point convertPoint (const geometry_msgs::Vector3 &point)
 Convert a Vector3 to a geometry_msg Point Note: Not thread safe but very convenient. More...
 
static geometry_msgs::Point convertPoint (const Eigen::Vector3d &point)
 Convert a Eigen point to a geometry_msg Point Note: Not thread safe but very convenient. More...
 
static Eigen::Vector3d convertPoint32 (const geometry_msgs::Point32 &point)
 Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient. More...
 
static 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. More...
 
static Eigen::Isometry3d convertPoint32ToPose (const geometry_msgs::Point32 &point)
 Convert a geometry_msg point (32bit) to an Eigen pose Note: Not thread safe but very convenient. More...
 
static geometry_msgs::Pose convertPointToPose (const geometry_msgs::Point &point)
 Add an identity rotation matrix to make a point have a full pose. More...
 
static Eigen::Isometry3d convertPointToPose (const Eigen::Vector3d &point)
 
static geometry_msgs::Pose convertPose (const Eigen::Isometry3d &pose)
 Convert an Eigen pose to a geometry_msg pose. More...
 
static Eigen::Isometry3d convertPose (const geometry_msgs::Pose &pose)
 Convert a geometry_msg pose to an Eigen pose Note: Not thread safe but very convenient. More...
 
static void convertPoseSafe (const Eigen::Isometry3d &pose, geometry_msgs::Pose &pose_msg)
 Convert an Eigen pose to a geometry_msg pose - thread safe. More...
 
static void convertPoseSafe (const geometry_msgs::Pose &pose_msg, Eigen::Isometry3d &pose)
 Convert a geometry_msg pose to an Eigen pose - thread safe. More...
 
static geometry_msgs::Point convertPoseToPoint (const Eigen::Isometry3d &pose)
 Convert an Eigen pose to a geometry_msg point Note: Not thread safe but very convenient. More...
 
static void convertToXYZRPY (const Eigen::Isometry3d &pose, std::vector< double > &xyzrpy)
 Convert an affine3d to xyz rpy components R-P-Y / X-Y-Z / 0-1-2 Euler Angle Standard. More...
 
static void convertToXYZRPY (const Eigen::Isometry3d &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. More...
 
static float fRand (float min, float max)
 
static void generateEmptyPose (geometry_msgs::Pose &pose)
 Create a pose of position (0,0,0) and quaternion (0,0,0,1) More...
 
static 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. More...
 
static void generateRandomPose (geometry_msgs::Pose &pose, RandomPoseBounds pose_bounds=RandomPoseBounds())
 Create a random pose within bounds of random_pose_bounds_. More...
 
static void generateRandomPose (Eigen::Isometry3d &pose, RandomPoseBounds pose_bounds=RandomPoseBounds())
 
static geometry_msgs::Pose getIdentityPose ()
 
static colors getRandColor ()
 Get a random color from the list of hardcoded enum color types. More...
 
static colors intToRvizColor (std::size_t color)
 Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL. More...
 
static rviz_visual_tools::scales intToRvizScale (std::size_t scale)
 Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL. More...
 
static int iRand (int min, int max)
 
static bool posesEqual (const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2, double threshold=0.000001)
 Test if two Eigen poses are close enough. More...
 
static void printTransform (const Eigen::Isometry3d &transform)
 Display in the console a transform in quaternions. More...
 
static void printTransformFull (const Eigen::Isometry3d &transform)
 Display in the console a transform with full 3x3 rotation matrix. More...
 
static void printTransformRPY (const Eigen::Isometry3d &transform)
 Display in the console a transform in roll pitch yaw. More...
 
static void printTranslation (const Eigen::Vector3d &translation)
 Display in the console the x,y,z values of a point. More...
 
static std::string scaleToString (scales scale)
 Convert an enum to its string name equivalent. More...
 
static double slerp (double start, double end, double range, double value)
 Interpolate from [start, end] with value of size steps with current value count. More...
 

Protected Attributes

double alpha_ = 1.0
 
visualization_msgs::Marker arrow_marker_
 
std::string base_frame_
 
bool batch_publishing_enabled_ = true
 
visualization_msgs::Marker block_marker_
 
visualization_msgs::Marker cuboid_marker_
 
visualization_msgs::Marker cylinder_marker_
 
bool frame_locking_enabled_ = false
 
double global_scale_ = 1.0
 
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_
 
ros::NodeHandle nh_
 
bool psychedelic_mode_ = false
 
ros::Publisher pub_rviz_markers_
 
bool pub_rviz_markers_connected_ = false
 
bool pub_rviz_markers_waited_ = false
 
RemoteControlPtr remote_control_
 
visualization_msgs::Marker reset_marker_
 
visualization_msgs::Marker sphere_marker_
 
visualization_msgs::Marker spheres_marker_
 
visualization_msgs::Marker text_marker_
 
visualization_msgs::Marker triangle_marker_
 

Static Protected Attributes

static const std::array< colors, 14 > all_rand_colors_
 
static RVIZ_VISUAL_TOOLS_DECL const std::string name_ = "visual_tools"
 

Private Member Functions

void initialize ()
 Shared function for initilization by constructors. More...
 
bool publishAxisInternal (const Eigen::Isometry3d &pose, double length=0.1, double radius=0.01, const std::string &ns="Axis")
 Display a red/green/blue coordinate axis - the 'internal' version does not do a batch publish. More...
 

Detailed Description

Definition at line 184 of file rviz_visual_tools.h.

Constructor & Destructor Documentation

◆ RvizVisualTools()

rviz_visual_tools::RvizVisualTools::RvizVisualTools ( std::string  base_frame,
std::string  marker_topic = RVIZ_MARKER_TOPIC,
ros::NodeHandle  nh = ros::NodeHandle("~") 
)
explicit

Constructor.

Parameters
base_frame- common base for all visualization markers, usually "/world" or "/odom"
marker_topic- rostopic to publish markers to - your Rviz display should match
nh- optional ros node handle - defaults to "~"

Definition at line 64 of file rviz_visual_tools.cpp.

◆ ~RvizVisualTools()

rviz_visual_tools::RvizVisualTools::~RvizVisualTools ( )
inline

Deconstructor.

Definition at line 203 of file rviz_visual_tools.h.

Member Function Documentation

◆ convertFromXYZRPY() [1/2]

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::convertFromXYZRPY ( double  tx,
double  ty,
double  tz,
double  rx,
double  ry,
double  rz,
EulerConvention  convention 
)
static

Converts scalar translations and rotations to an Eigen Frame. This is achieved by chaining a translation with individual euler rotations in ZYX order (this is equivalent to fixed rotatins XYZ) http://en.wikipedia.org/wiki/Euler_angles#Conversion_between_intrinsic_and_extrinsic_rotations Euler conversion code sourced from Descartes, Copyright (c) 2014, Southwest Research Institute.

Parameters
tx,ty,tz- translations in x, y, z respectively
rx,ry,rz- rotations about x, y, z, respectively
convention- default is rviz_visual_tools::XYZ

Definition at line 2544 of file rviz_visual_tools.cpp.

◆ convertFromXYZRPY() [2/2]

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::convertFromXYZRPY ( const std::vector< double > &  transform6,
EulerConvention  convention 
)
static

Definition at line 2574 of file rviz_visual_tools.cpp.

◆ convertPoint() [1/3]

Eigen::Vector3d rviz_visual_tools::RvizVisualTools::convertPoint ( const geometry_msgs::Point point)
static

Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.

Parameters
point
Returns
converted pose

Definition at line 2499 of file rviz_visual_tools.cpp.

◆ convertPoint() [2/3]

geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoint ( const geometry_msgs::Vector3 &  point)
static

Convert a Vector3 to a geometry_msg Point Note: Not thread safe but very convenient.

Parameters
point
Returns
converted point

Definition at line 2526 of file rviz_visual_tools.cpp.

◆ convertPoint() [3/3]

geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoint ( const Eigen::Vector3d &  point)
static

Convert a Eigen point to a geometry_msg Point Note: Not thread safe but very convenient.

Parameters
point
Returns
converted point

Definition at line 2535 of file rviz_visual_tools.cpp.

◆ convertPoint32() [1/2]

Eigen::Vector3d rviz_visual_tools::RvizVisualTools::convertPoint32 ( const geometry_msgs::Point32 &  point)
static

Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.

Parameters
point
Returns
converted pose

Definition at line 2508 of file rviz_visual_tools.cpp.

◆ convertPoint32() [2/2]

geometry_msgs::Point32 rviz_visual_tools::RvizVisualTools::convertPoint32 ( const Eigen::Vector3d &  point)
static

Convert an Eigen point to a 32 bit geometry_msg point Note: Not thread safe but very convenient.

Parameters
point
Returns
converted pose

Definition at line 2517 of file rviz_visual_tools.cpp.

◆ convertPoint32ToPose()

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::convertPoint32ToPose ( const geometry_msgs::Point32 &  point)
static

Convert a geometry_msg point (32bit) to an Eigen pose Note: Not thread safe but very convenient.

Parameters
pose
Returns
converted point with default rotation matrix

Definition at line 2463 of file rviz_visual_tools.cpp.

◆ convertPointToPose() [1/2]

geometry_msgs::Pose rviz_visual_tools::RvizVisualTools::convertPointToPose ( const geometry_msgs::Point point)
static

Add an identity rotation matrix to make a point have a full pose.

Definition at line 2473 of file rviz_visual_tools.cpp.

◆ convertPointToPose() [2/2]

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::convertPointToPose ( const Eigen::Vector3d &  point)
static

Definition at line 2484 of file rviz_visual_tools.cpp.

◆ convertPose() [1/2]

geometry_msgs::Pose rviz_visual_tools::RvizVisualTools::convertPose ( const Eigen::Isometry3d &  pose)
static

Convert an Eigen pose to a geometry_msg pose.

Parameters
pose
Returns
converted pose

Definition at line 2439 of file rviz_visual_tools.cpp.

◆ convertPose() [2/2]

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::convertPose ( const geometry_msgs::Pose pose)
static

Convert a geometry_msg pose to an Eigen pose Note: Not thread safe but very convenient.

Parameters
ROSmsg pose
Returns
converted pose

Definition at line 2451 of file rviz_visual_tools.cpp.

◆ convertPoseSafe() [1/2]

void rviz_visual_tools::RvizVisualTools::convertPoseSafe ( const Eigen::Isometry3d &  pose,
geometry_msgs::Pose pose_msg 
)
static

Convert an Eigen pose to a geometry_msg pose - thread safe.

Parameters
Eigenpose - input
ROSmsg pose - output

Definition at line 2446 of file rviz_visual_tools.cpp.

◆ convertPoseSafe() [2/2]

void rviz_visual_tools::RvizVisualTools::convertPoseSafe ( const geometry_msgs::Pose pose_msg,
Eigen::Isometry3d &  pose 
)
static

Convert a geometry_msg pose to an Eigen pose - thread safe.

Parameters
ROSmsg pose - input
Eigenpose - output

Definition at line 2458 of file rviz_visual_tools.cpp.

◆ convertPoseToPoint()

geometry_msgs::Point rviz_visual_tools::RvizVisualTools::convertPoseToPoint ( const Eigen::Isometry3d &  pose)
static

Convert an Eigen pose to a geometry_msg point Note: Not thread safe but very convenient.

Parameters
pose
Returns
converted point with orientation discarded

Definition at line 2492 of file rviz_visual_tools.cpp.

◆ convertToXYZRPY() [1/2]

void rviz_visual_tools::RvizVisualTools::convertToXYZRPY ( const Eigen::Isometry3d &  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.

Parameters
inputEigen pose
outputvector of size 6 in order xyz rpy

Definition at line 2586 of file rviz_visual_tools.cpp.

◆ convertToXYZRPY() [2/2]

void rviz_visual_tools::RvizVisualTools::convertToXYZRPY ( const Eigen::Isometry3d &  pose,
double &  x,
double &  y,
double &  z,
double &  roll,
double &  pitch,
double &  yaw 
)
static

Definition at line 2592 of file rviz_visual_tools.cpp.

◆ createRandColor()

std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::createRandColor ( ) const

Create a random color that is not too light.

Returns
the RGB message of a random color

Definition at line 579 of file rviz_visual_tools.cpp.

◆ deleteAllMarkers()

bool rviz_visual_tools::RvizVisualTools::deleteAllMarkers ( )

Tell Rviz to clear all markers on a particular display.

Definition at line 78 of file rviz_visual_tools.cpp.

◆ dRand()

double rviz_visual_tools::RvizVisualTools::dRand ( double  min,
double  max 
)
static

Get random between min and max.

Definition at line 2719 of file rviz_visual_tools.cpp.

◆ enableBatchPublishing()

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 trigger() is called.

Definition at line 843 of file rviz_visual_tools.cpp.

◆ enableFrameLocking()

void rviz_visual_tools::RvizVisualTools::enableFrameLocking ( bool  enable = true)

Enable frame locking - useful for when the markers is attached to a moving TF, the marker will be re-transformed into its frame every time-step.

Definition at line 848 of file rviz_visual_tools.cpp.

◆ fRand()

float rviz_visual_tools::RvizVisualTools::fRand ( float  min,
float  max 
)
static

Definition at line 2725 of file rviz_visual_tools.cpp.

◆ generateEmptyPose()

void rviz_visual_tools::RvizVisualTools::generateEmptyPose ( geometry_msgs::Pose pose)
static

Create a pose of position (0,0,0) and quaternion (0,0,0,1)

Parameters
Poseto fill in

Definition at line 2674 of file rviz_visual_tools.cpp.

◆ generateRandomCuboid()

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() 
)
static

Create a random rectangular cuboid of some shape.

Definition at line 2613 of file rviz_visual_tools.cpp.

◆ generateRandomPose() [1/2]

void rviz_visual_tools::RvizVisualTools::generateRandomPose ( geometry_msgs::Pose pose,
RandomPoseBounds  pose_bounds = RandomPoseBounds() 
)
static

Create a random pose within bounds of random_pose_bounds_.

Parameters
Poseto fill in options bounds on the pose to generate

Definition at line 2606 of file rviz_visual_tools.cpp.

◆ generateRandomPose() [2/2]

void rviz_visual_tools::RvizVisualTools::generateRandomPose ( Eigen::Isometry3d &  pose,
RandomPoseBounds  pose_bounds = RandomPoseBounds() 
)
static

Definition at line 2626 of file rviz_visual_tools.cpp.

◆ getBaseFrame()

const std::string rviz_visual_tools::RvizVisualTools::getBaseFrame ( ) const
inline

Get the base frame.

Returns
name of base frame

Definition at line 334 of file rviz_visual_tools.h.

◆ getCenterPoint()

Eigen::Vector3d rviz_visual_tools::RvizVisualTools::getCenterPoint ( const Eigen::Vector3d &  a,
const Eigen::Vector3d &  b 
) const

Find the center between to points.

Parameters
pointa - x,y,z in space of a point
pointb - x,y,z in space of a point
Returns
center point

Definition at line 712 of file rviz_visual_tools.cpp.

◆ getColor()

std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColor ( colors  color) const

Get the RGB value of standard colors.

Parameters
color- an enum pre-defined name of a color
Returns
the RGB message equivalent

Definition at line 371 of file rviz_visual_tools.cpp.

◆ getColorScale()

std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColorScale ( double  value) const

Convert a value from [0,1] to a color Green->Red.

Returns
interpolated color

Definition at line 613 of file rviz_visual_tools.cpp.

◆ getGlobalScale()

double rviz_visual_tools::RvizVisualTools::getGlobalScale ( ) const
inline

Getter for the global scale used for changing size of all markers.

Definition at line 352 of file rviz_visual_tools.h.

◆ getIdentityPose()

geometry_msgs::Pose rviz_visual_tools::RvizVisualTools::getIdentityPose ( )
static

Definition at line 2688 of file rviz_visual_tools.cpp.

◆ getPsychedelicMode()

bool rviz_visual_tools::RvizVisualTools::getPsychedelicMode ( ) const
inline

Getter for PsychedelicMode.

Definition at line 1037 of file rviz_visual_tools.h.

◆ getRandColor()

colors rviz_visual_tools::RvizVisualTools::getRandColor ( )
static

Get a random color from the list of hardcoded enum color types.

Returns
Random color from colors

Definition at line 365 of file rviz_visual_tools.cpp.

◆ getRemoteControl()

RemoteControlPtr & rviz_visual_tools::RvizVisualTools::getRemoteControl ( )

Ability to load remote control on the fly.

Definition at line 2776 of file rviz_visual_tools.cpp.

◆ getScale()

geometry_msgs::Vector3 rviz_visual_tools::RvizVisualTools::getScale ( scales  scale,
double  marker_scale = 1.0 
) const

Get the rviz marker scale of standard sizes.

Parameters
scale- an enum pre-defined name of a size
marker_scale- amount to scale the scale for accounting for different types of markers
Returns
vector of 3 scales

Definition at line 660 of file rviz_visual_tools.cpp.

◆ getVectorBetweenPoints()

Eigen::Isometry3d rviz_visual_tools::RvizVisualTools::getVectorBetweenPoints ( const Eigen::Vector3d &  a,
const Eigen::Vector3d &  b 
) const

Create a vector that points from point a to point b.

Parameters
pointa - x,y,z in space of a point
pointb - x,y,z in space of a point
Returns
vector from a to b

Definition at line 721 of file rviz_visual_tools.cpp.

◆ initialize()

void rviz_visual_tools::RvizVisualTools::initialize ( )
private

Shared function for initilization by constructors.

Definition at line 70 of file rviz_visual_tools.cpp.

◆ intToRvizColor()

colors rviz_visual_tools::RvizVisualTools::intToRvizColor ( std::size_t  color)
static

Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL.

Definition at line 504 of file rviz_visual_tools.cpp.

◆ intToRvizScale()

scales rviz_visual_tools::RvizVisualTools::intToRvizScale ( std::size_t  scale)
static

Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL.

Definition at line 535 of file rviz_visual_tools.cpp.

◆ iRand()

int rviz_visual_tools::RvizVisualTools::iRand ( int  min,
int  max 
)
static

Definition at line 2731 of file rviz_visual_tools.cpp.

◆ loadMarkerPub()

void rviz_visual_tools::RvizVisualTools::loadMarkerPub ( bool  wait_for_subscriber = false,
bool  latched = false 
)

Load publishers as needed.

Parameters
wait_for_subscriber- whether a sleep for loop should be used to check for connectivity to an external node before proceeding

Definition at line 271 of file rviz_visual_tools.cpp.

◆ loadRemoteControl()

void rviz_visual_tools::RvizVisualTools::loadRemoteControl ( )

Pre-load remote control.

Definition at line 2785 of file rviz_visual_tools.cpp.

◆ loadRvizMarkers()

bool rviz_visual_tools::RvizVisualTools::loadRvizMarkers ( )

Pre-load rviz markers for better efficiency.

Returns
converted pose *
true on sucess

Definition at line 99 of file rviz_visual_tools.cpp.

◆ posesEqual()

bool rviz_visual_tools::RvizVisualTools::posesEqual ( const Eigen::Isometry3d &  pose1,
const Eigen::Isometry3d &  pose2,
double  threshold = 0.000001 
)
static

Test if two Eigen poses are close enough.

Parameters
pose1
pose2
threshold- how close in value they must be in order to be considered the same
Returns
true if equal

Definition at line 2704 of file rviz_visual_tools.cpp.

◆ printTransform()

void rviz_visual_tools::RvizVisualTools::printTransform ( const Eigen::Isometry3d &  transform)
static

Display in the console a transform in quaternions.

Definition at line 2748 of file rviz_visual_tools.cpp.

◆ printTransformFull()

void rviz_visual_tools::RvizVisualTools::printTransformFull ( const Eigen::Isometry3d &  transform)
static

Display in the console a transform with full 3x3 rotation matrix.

Definition at line 2764 of file rviz_visual_tools.cpp.

◆ printTransformRPY()

void rviz_visual_tools::RvizVisualTools::printTransformRPY ( const Eigen::Isometry3d &  transform)
static

Display in the console a transform in roll pitch yaw.

Definition at line 2756 of file rviz_visual_tools.cpp.

◆ printTranslation()

void rviz_visual_tools::RvizVisualTools::printTranslation ( const Eigen::Vector3d &  translation)
static

Display in the console the x,y,z values of a point.

Definition at line 2743 of file rviz_visual_tools.cpp.

◆ prompt()

void rviz_visual_tools::RvizVisualTools::prompt ( const std::string &  msg)

Wait for user feedback i.e. through a button or joystick.

Definition at line 2771 of file rviz_visual_tools.cpp.

◆ publishArrow() [1/4]

bool rviz_visual_tools::RvizVisualTools::publishArrow ( const Eigen::Isometry3d &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0,
std::size_t  id = 0 
)

Display an arrow along the x-axis of a pose.

Parameters
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. if zero, will auto set with scale
start- the starting point of the arrow
end- the ending point of the arrow
Returns
true on success

Definition at line 1292 of file rviz_visual_tools.cpp.

◆ publishArrow() [2/4]

bool rviz_visual_tools::RvizVisualTools::publishArrow ( const geometry_msgs::Pose pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0,
std::size_t  id = 0 
)

Definition at line 1298 of file rviz_visual_tools.cpp.

◆ publishArrow() [3/4]

bool rviz_visual_tools::RvizVisualTools::publishArrow ( const geometry_msgs::PoseStamped &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0,
std::size_t  id = 0 
)

Definition at line 1332 of file rviz_visual_tools.cpp.

◆ publishArrow() [4/4]

bool rviz_visual_tools::RvizVisualTools::publishArrow ( const geometry_msgs::Point start,
const geometry_msgs::Point end,
colors  color = BLUE,
scales  scale = MEDIUM,
std::size_t  id = 0 
)

Definition at line 1368 of file rviz_visual_tools.cpp.

◆ publishAxis() [1/4]

bool rviz_visual_tools::RvizVisualTools::publishAxis ( const geometry_msgs::Pose pose,
scales  scale = MEDIUM,
const std::string &  ns = "Axis" 
)

Display a red/green/blue coordinate frame axis.

Parameters
pose- the location to publish the marker with respect to the base frame
scale- size of axis
length- geometry of cylinder
radius- geometry of cylinder
ns- namespace
Returns
true on success

Definition at line 1421 of file rviz_visual_tools.cpp.

◆ publishAxis() [2/4]

bool rviz_visual_tools::RvizVisualTools::publishAxis ( const Eigen::Isometry3d &  pose,
scales  scale = MEDIUM,
const std::string &  ns = "Axis" 
)

Definition at line 1427 of file rviz_visual_tools.cpp.

◆ publishAxis() [3/4]

bool rviz_visual_tools::RvizVisualTools::publishAxis ( const geometry_msgs::Pose pose,
double  length,
double  radius = 0.01,
const std::string &  ns = "Axis" 
)

Definition at line 1433 of file rviz_visual_tools.cpp.

◆ publishAxis() [4/4]

bool rviz_visual_tools::RvizVisualTools::publishAxis ( const Eigen::Isometry3d &  pose,
double  length,
double  radius = 0.01,
const std::string &  ns = "Axis" 
)

Definition at line 1438 of file rviz_visual_tools.cpp.

◆ publishAxisInternal()

bool rviz_visual_tools::RvizVisualTools::publishAxisInternal ( const Eigen::Isometry3d &  pose,
double  length = 0.1,
double  radius = 0.01,
const std::string &  ns = "Axis" 
)
private

Display a red/green/blue coordinate axis - the 'internal' version does not do a batch publish.

Parameters
pose- the location to publish the marker with respect to the base frame
length- geometry of cylinder
radius- geometry of cylinder
ns- namespace
Returns
true on success

Definition at line 1447 of file rviz_visual_tools.cpp.

◆ publishAxisLabeled() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishAxisLabeled ( const Eigen::Isometry3d &  pose,
const std::string &  label,
scales  scale = MEDIUM,
colors  color = WHITE 
)

Display a marker of a coordinate frame axis with a text label describing it.

Parameters
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
Returns
true on success

Definition at line 1401 of file rviz_visual_tools.cpp.

◆ publishAxisLabeled() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishAxisLabeled ( const geometry_msgs::Pose pose,
const std::string &  label,
scales  scale = MEDIUM,
colors  color = WHITE 
)

Definition at line 1407 of file rviz_visual_tools.cpp.

◆ publishAxisPath() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishAxisPath ( const EigenSTL::vector_Isometry3d path,
scales  scale = MEDIUM,
const std::string &  ns = "Axis Path" 
)

Display a series of red/green/blue coordinate axis along a path.

Parameters
path- the location to publish each marker with respect to the base frame
length- geometry of cylinder
radius- geometry of cylinder
ns- namespace
Returns
true on success

Definition at line 1470 of file rviz_visual_tools.cpp.

◆ publishAxisPath() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishAxisPath ( const EigenSTL::vector_Isometry3d path,
double  length = 0.1,
double  radius = 0.01,
const std::string &  ns = "Axis Path" 
)

Definition at line 1482 of file rviz_visual_tools.cpp.

◆ publishCone() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishCone ( const Eigen::Isometry3d &  pose,
double  angle,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Display a cone of a given angle along the x-axis.

Parameters
pose- the location and orientation of the cone
color- color of the cone
scale- size of the cone
Returns
true on success

Definition at line 925 of file rviz_visual_tools.cpp.

◆ publishCone() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishCone ( const geometry_msgs::Pose pose,
double  angle,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Definition at line 930 of file rviz_visual_tools.cpp.

◆ publishCuboid() [1/4]

bool rviz_visual_tools::RvizVisualTools::publishCuboid ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
colors  color = BLUE 
)

Display a rectangular cuboid.

Parameters
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
Returns
true on success

Definition at line 1640 of file rviz_visual_tools.cpp.

◆ publishCuboid() [2/4]

bool rviz_visual_tools::RvizVisualTools::publishCuboid ( const geometry_msgs::Point point1,
const geometry_msgs::Point point2,
colors  color = BLUE,
const std::string &  ns = "Cuboid",
std::size_t  id = 0 
)

Definition at line 1645 of file rviz_visual_tools.cpp.

◆ publishCuboid() [3/4]

bool rviz_visual_tools::RvizVisualTools::publishCuboid ( const geometry_msgs::Pose pose,
double  depth,
double  width,
double  height,
colors  color = BLUE 
)

Display a rectangular cuboid.

Parameters
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
Returns
true on success

Definition at line 1699 of file rviz_visual_tools.cpp.

◆ publishCuboid() [4/4]

bool rviz_visual_tools::RvizVisualTools::publishCuboid ( const Eigen::Isometry3d &  pose,
double  depth,
double  width,
double  height,
colors  color = BLUE 
)

Definition at line 1693 of file rviz_visual_tools.cpp.

◆ publishCylinder() [1/6]

bool rviz_visual_tools::RvizVisualTools::publishCylinder ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Cylinder" 
)

Display a marker of a cylinder.

Parameters
point1- starting side of cylinder
point2- end side of cylinder
color- an enum pre-defined name of a color
radius- geometry of cylinder
Returns
true on success

Definition at line 1494 of file rviz_visual_tools.cpp.

◆ publishCylinder() [2/6]

bool rviz_visual_tools::RvizVisualTools::publishCylinder ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
colors  color,
double  radius = 0.01,
const std::string &  ns = "Cylinder" 
)

Definition at line 1501 of file rviz_visual_tools.cpp.

◆ publishCylinder() [3/6]

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 1507 of file rviz_visual_tools.cpp.

◆ publishCylinder() [4/6]

bool rviz_visual_tools::RvizVisualTools::publishCylinder ( const Eigen::Isometry3d &  pose,
colors  color = BLUE,
double  height = 0.1,
double  radius = 0.01,
const std::string &  ns = "Cylinder" 
)

Display a marker of a cylinder.

Parameters
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
Returns
true on success

Definition at line 1529 of file rviz_visual_tools.cpp.

◆ publishCylinder() [5/6]

bool rviz_visual_tools::RvizVisualTools::publishCylinder ( const geometry_msgs::Pose pose,
colors  color = BLUE,
double  height = 0.1,
double  radius = 0.01,
const std::string &  ns = "Cylinder" 
)

Definition at line 1535 of file rviz_visual_tools.cpp.

◆ publishCylinder() [6/6]

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 1541 of file rviz_visual_tools.cpp.

◆ publishGraph()

bool rviz_visual_tools::RvizVisualTools::publishGraph ( const graph_msgs::GeometryGraph &  graph,
colors  color,
double  radius 
)

Display a graph.

Parameters
graphof nodes and edges
color- an enum pre-defined name of a color
radius- width of cylinders
Returns
true on success

Definition at line 1608 of file rviz_visual_tools.cpp.

◆ publishLine() [1/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const Eigen::Isometry3d &  point1,
const Eigen::Isometry3d &  point2,
colors  color = BLUE,
scales  scale = MEDIUM 
)

Display a marker of line.

Parameters
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
Returns
true on success

Definition at line 1740 of file rviz_visual_tools.cpp.

◆ publishLine() [2/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
colors  color = BLUE,
scales  scale = MEDIUM 
)

Definition at line 1746 of file rviz_visual_tools.cpp.

◆ publishLine() [3/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
colors  color,
double  radius 
)

Definition at line 1751 of file rviz_visual_tools.cpp.

◆ publishLine() [4/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
const std_msgs::ColorRGBA &  color,
scales  scale = MEDIUM 
)

Definition at line 1761 of file rviz_visual_tools.cpp.

◆ publishLine() [5/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const Eigen::Vector3d &  point1,
const Eigen::Vector3d &  point2,
const std_msgs::ColorRGBA &  color,
double  radius 
)

Definition at line 1767 of file rviz_visual_tools.cpp.

◆ publishLine() [6/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const geometry_msgs::Point point1,
const geometry_msgs::Point point2,
colors  color = BLUE,
scales  scale = MEDIUM 
)

Definition at line 1777 of file rviz_visual_tools.cpp.

◆ publishLine() [7/8]

bool rviz_visual_tools::RvizVisualTools::publishLine ( const geometry_msgs::Point point1,
const geometry_msgs::Point point2,
const std_msgs::ColorRGBA &  color,
scales  scale = MEDIUM 
)

Definition at line 1783 of file rviz_visual_tools.cpp.

◆ publishLine() [8/8]

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 1789 of file rviz_visual_tools.cpp.

◆ publishLines() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishLines ( const EigenSTL::vector_Vector3d aPoints,
const EigenSTL::vector_Vector3d bPoints,
const std::vector< colors > &  colors,
scales  scale = MEDIUM 
)

Display a marker of lines.

Parameters
aPoints- x,y,z of start of line, as a vector
bPoints- x,y,z of end of line, as a vector
colors- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
Returns
true on success

Definition at line 1807 of file rviz_visual_tools.cpp.

◆ publishLines() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishLines ( const std::vector< geometry_msgs::Point > &  aPoints,
const std::vector< geometry_msgs::Point > &  bPoints,
const std::vector< std_msgs::ColorRGBA > &  colors,
const geometry_msgs::Vector3 &  scale 
)

Definition at line 1831 of file rviz_visual_tools.cpp.

◆ publishLineStrip()

bool rviz_visual_tools::RvizVisualTools::publishLineStrip ( const std::vector< geometry_msgs::Point > &  path,
colors  color = RED,
scales  scale = MEDIUM,
const std::string &  ns = "Path" 
)

Display a series of connected lines using the LINE_STRIP method - deprecated because visual bugs.

Parameters
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
Returns
true on success

Definition at line 1864 of file rviz_visual_tools.cpp.

◆ publishMarker()

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.

Parameters
marker- a pre-made marker ready to be published
Returns
true on success

Definition at line 828 of file rviz_visual_tools.cpp.

◆ publishMarkers()

bool rviz_visual_tools::RvizVisualTools::publishMarkers ( visualization_msgs::MarkerArray &  markers)

Display an array of markers, allows reuse of the ROS publisher.

Parameters
markers
Returns
true on success

Definition at line 880 of file rviz_visual_tools.cpp.

◆ publishMesh() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishMesh ( const Eigen::Isometry3d &  pose,
const std::string &  file_name,
colors  color = CLEAR,
double  scale = 1,
const std::string &  ns = "mesh",
std::size_t  id = 0 
)

Display a mesh from file.

Parameters
pose- the location to publish the marker with respect to the base frame
filename 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
Returns
true on success

Definition at line 1564 of file rviz_visual_tools.cpp.

◆ publishMesh() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishMesh ( const geometry_msgs::Pose pose,
const std::string &  file_name,
colors  color = CLEAR,
double  scale = 1,
const std::string &  ns = "mesh",
std::size_t  id = 0 
)

Definition at line 1570 of file rviz_visual_tools.cpp.

◆ publishPath() [1/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const std::vector< geometry_msgs::Pose > &  path,
colors  color = RED,
scales  scale = MEDIUM,
const std::string &  ns = "Path" 
)

Display a marker of a series of connected cylinders.

Parameters
path- a series of points to connect with cylinders
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
ns- namespace of marker
Returns
true on success

Definition at line 1898 of file rviz_visual_tools.cpp.

◆ publishPath() [2/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const std::vector< geometry_msgs::Point > &  path,
colors  color,
scales  scale,
const std::string &  ns = "Path" 
)

Definition at line 1910 of file rviz_visual_tools.cpp.

◆ publishPath() [3/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Isometry3d path,
colors  color,
scales  scale,
const std::string &  ns = "Path" 
)

Definition at line 1916 of file rviz_visual_tools.cpp.

◆ publishPath() [4/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Vector3d path,
colors  color,
scales  scale,
const std::string &  ns = "Path" 
)

Definition at line 1922 of file rviz_visual_tools.cpp.

◆ publishPath() [5/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const std::vector< geometry_msgs::Point > &  path,
colors  color = RED,
double  radius = 0.01,
const std::string &  ns = "Path" 
)

Definition at line 1928 of file rviz_visual_tools.cpp.

◆ publishPath() [6/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Vector3d path,
colors  color = RED,
double  radius = 0.01,
const std::string &  ns = "Path" 
)

Definition at line 1946 of file rviz_visual_tools.cpp.

◆ publishPath() [7/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Isometry3d path,
colors  color = RED,
double  radius = 0.01,
const std::string &  ns = "Path" 
)

Definition at line 1964 of file rviz_visual_tools.cpp.

◆ publishPath() [8/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Vector3d path,
const std::vector< colors > &  colors,
double  radius = 0.01,
const std::string &  ns = "Path" 
)

Display a marker of a series of connected colored cylinders.

Parameters
path- a series of points to connect with cylinders
colors- a series of colors
radius- the radius of the cylinders
ns- namespace of marker
Returns
true on success
Note
path and colors vectors must be the same size

Definition at line 1982 of file rviz_visual_tools.cpp.

◆ publishPath() [9/9]

bool rviz_visual_tools::RvizVisualTools::publishPath ( const EigenSTL::vector_Vector3d path,
const std::vector< std_msgs::ColorRGBA > &  colors,
double  radius,
const std::string &  ns = "Path" 
)

Definition at line 2007 of file rviz_visual_tools.cpp.

◆ publishPolygon()

bool rviz_visual_tools::RvizVisualTools::publishPolygon ( const geometry_msgs::Polygon &  polygon,
colors  color = RED,
scales  scale = MEDIUM,
const std::string &  ns = "Polygon" 
)

Display a marker of a polygon.

Parameters
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
Returns
true on success

Definition at line 2032 of file rviz_visual_tools.cpp.

◆ publishSphere() [1/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const Eigen::Isometry3d &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Display a marker of a sphere.

Parameters
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
Returns
true on success

Definition at line 1109 of file rviz_visual_tools.cpp.

◆ publishSphere() [2/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const Eigen::Vector3d &  point,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1115 of file rviz_visual_tools.cpp.

◆ publishSphere() [3/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const Eigen::Vector3d &  point,
colors  color,
double  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1123 of file rviz_visual_tools.cpp.

◆ publishSphere() [4/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const geometry_msgs::Point point,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1131 of file rviz_visual_tools.cpp.

◆ publishSphere() [5/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const geometry_msgs::Pose pose,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1139 of file rviz_visual_tools.cpp.

◆ publishSphere() [6/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const geometry_msgs::Pose pose,
colors  color,
double  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1145 of file rviz_visual_tools.cpp.

◆ publishSphere() [7/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const geometry_msgs::Pose pose,
colors  color,
const geometry_msgs::Vector3  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1155 of file rviz_visual_tools.cpp.

◆ publishSphere() [8/11]

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",
std::size_t  id = 0 
)

Definition at line 1175 of file rviz_visual_tools.cpp.

◆ publishSphere() [9/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const Eigen::Isometry3d &  pose,
const std_msgs::ColorRGBA &  color,
const geometry_msgs::Vector3  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1161 of file rviz_visual_tools.cpp.

◆ publishSphere() [10/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const Eigen::Vector3d &  point,
const std_msgs::ColorRGBA &  color,
const geometry_msgs::Vector3  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1167 of file rviz_visual_tools.cpp.

◆ publishSphere() [11/11]

bool rviz_visual_tools::RvizVisualTools::publishSphere ( const geometry_msgs::PoseStamped &  pose,
colors  color,
const geometry_msgs::Vector3  scale,
const std::string &  ns = "Sphere",
std::size_t  id = 0 
)

Definition at line 1200 of file rviz_visual_tools.cpp.

◆ publishSpheres() [1/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const EigenSTL::vector_Vector3d points,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Spheres" 
)

Display a marker of a series of spheres.

Parameters
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
Returns
true on success

Definition at line 2283 of file rviz_visual_tools.cpp.

◆ publishSpheres() [2/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const EigenSTL::vector_Vector3d points,
colors  color,
double  scale = 0.1,
const std::string &  ns = "Spheres" 
)

Definition at line 2296 of file rviz_visual_tools.cpp.

◆ publishSpheres() [3/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const std::vector< geometry_msgs::Point > &  points,
colors  color = BLUE,
scales  scale = MEDIUM,
const std::string &  ns = "Spheres" 
)

Definition at line 2319 of file rviz_visual_tools.cpp.

◆ publishSpheres() [4/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const std::vector< geometry_msgs::Point > &  points,
colors  color = BLUE,
double  scale = 0.1,
const std::string &  ns = "Spheres" 
)

Definition at line 2309 of file rviz_visual_tools.cpp.

◆ publishSpheres() [5/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const std::vector< geometry_msgs::Point > &  points,
colors  color,
const geometry_msgs::Vector3 &  scale,
const std::string &  ns = "Spheres" 
)

Definition at line 2325 of file rviz_visual_tools.cpp.

◆ publishSpheres() [6/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const EigenSTL::vector_Vector3d points,
const std::vector< colors > &  colors,
scales  scale = MEDIUM,
const std::string &  ns = "Spheres" 
)

Display a marker of a series of spheres, with the possibility of different colors.

Parameters
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
Returns
true on success

Definition at line 2351 of file rviz_visual_tools.cpp.

◆ publishSpheres() [7/7]

bool rviz_visual_tools::RvizVisualTools::publishSpheres ( const std::vector< geometry_msgs::Point > &  points,
const std::vector< std_msgs::ColorRGBA > &  colors,
const geometry_msgs::Vector3 &  scale,
const std::string &  ns = "Spheres" 
)

Definition at line 2370 of file rviz_visual_tools.cpp.

◆ publishText() [1/4]

bool rviz_visual_tools::RvizVisualTools::publishText ( const Eigen::Isometry3d &  pose,
const std::string &  text,
colors  color = WHITE,
scales  scale = MEDIUM,
bool  static_id = true 
)

Display a marker of a text.

Parameters
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
Returns
true on success

Definition at line 2388 of file rviz_visual_tools.cpp.

◆ publishText() [2/4]

bool rviz_visual_tools::RvizVisualTools::publishText ( const Eigen::Isometry3d &  pose,
const std::string &  text,
colors  color,
const geometry_msgs::Vector3  scale,
bool  static_id = true 
)

Definition at line 2394 of file rviz_visual_tools.cpp.

◆ publishText() [3/4]

bool rviz_visual_tools::RvizVisualTools::publishText ( const geometry_msgs::Pose pose,
const std::string &  text,
colors  color = WHITE,
scales  scale = MEDIUM,
bool  static_id = true 
)

Definition at line 2400 of file rviz_visual_tools.cpp.

◆ publishText() [4/4]

bool rviz_visual_tools::RvizVisualTools::publishText ( const geometry_msgs::Pose pose,
const std::string &  text,
colors  color,
const geometry_msgs::Vector3  scale,
bool  static_id = true 
)

Definition at line 2406 of file rviz_visual_tools.cpp.

◆ publishWireframeCuboid() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishWireframeCuboid ( const Eigen::Isometry3d &  pose,
double  depth,
double  width,
double  height,
colors  color = BLUE,
const std::string &  ns = "Wireframe Cuboid",
std::size_t  id = 0 
)

Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box.

Parameters
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
Returns
true on success

Definition at line 2056 of file rviz_visual_tools.cpp.

◆ publishWireframeCuboid() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishWireframeCuboid ( const Eigen::Isometry3d &  pose,
const Eigen::Vector3d &  min_point,
const Eigen::Vector3d &  max_point,
colors  color = BLUE,
const std::string &  ns = "Wireframe Cuboid",
std::size_t  id = 0 
)

Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box.

Parameters
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
Returns
true on success

Definition at line 2065 of file rviz_visual_tools.cpp.

◆ publishWireframeRectangle() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishWireframeRectangle ( const Eigen::Isometry3d &  pose,
double  height,
double  width,
colors  color = BLUE,
scales  scale = MEDIUM,
std::size_t  id = 0 
)

Publish outline of a rectangle.

Parameters
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
Returns
true on success

Definition at line 2172 of file rviz_visual_tools.cpp.

◆ publishWireframeRectangle() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishWireframeRectangle ( const Eigen::Isometry3d &  pose,
const Eigen::Vector3d &  p1_in,
const Eigen::Vector3d &  p2_in,
const Eigen::Vector3d &  p3_in,
const Eigen::Vector3d &  p4_in,
colors  color,
scales  scale 
)

Definition at line 2230 of file rviz_visual_tools.cpp.

◆ publishXArrow() [1/3]

bool rviz_visual_tools::RvizVisualTools::publishXArrow ( const Eigen::Isometry3d &  pose,
colors  color = RED,
scales  scale = MEDIUM,
double  length = 0.0 
)

Display an arrow along the x-axis of a pose.

Parameters
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, if zero, will auto set with scale
Returns
true on success

Definition at line 1227 of file rviz_visual_tools.cpp.

◆ publishXArrow() [2/3]

bool rviz_visual_tools::RvizVisualTools::publishXArrow ( const geometry_msgs::Pose pose,
colors  color = RED,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1232 of file rviz_visual_tools.cpp.

◆ publishXArrow() [3/3]

bool rviz_visual_tools::RvizVisualTools::publishXArrow ( const geometry_msgs::PoseStamped &  pose,
colors  color = RED,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1237 of file rviz_visual_tools.cpp.

◆ publishXYPlane() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishXYPlane ( const Eigen::Isometry3d &  pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Display the XY plane of a given pose.

Parameters
pose- the position of the plane
color- the color of the plane
scale- the size of the vizualized plane
Returns
true on success

Definition at line 971 of file rviz_visual_tools.cpp.

◆ publishXYPlane() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishXYPlane ( const geometry_msgs::Pose pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Definition at line 976 of file rviz_visual_tools.cpp.

◆ publishXZPlane() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishXZPlane ( const Eigen::Isometry3d &  pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Display the XY plane of a given pose.

Parameters
pose- the position of the plane
color- the color of the plane
scale- the size of the vizualized plane
Returns
true on success

Definition at line 1017 of file rviz_visual_tools.cpp.

◆ publishXZPlane() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishXZPlane ( const geometry_msgs::Pose pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Definition at line 1022 of file rviz_visual_tools.cpp.

◆ publishYArrow() [1/3]

bool rviz_visual_tools::RvizVisualTools::publishYArrow ( const Eigen::Isometry3d &  pose,
colors  color = GREEN,
scales  scale = MEDIUM,
double  length = 0.0 
)

Display an arrow along the y-axis of a pose.

Parameters
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, if zero, will auto set with scale
Returns
true on success

Definition at line 1242 of file rviz_visual_tools.cpp.

◆ publishYArrow() [2/3]

bool rviz_visual_tools::RvizVisualTools::publishYArrow ( const geometry_msgs::Pose pose,
colors  color = GREEN,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1248 of file rviz_visual_tools.cpp.

◆ publishYArrow() [3/3]

bool rviz_visual_tools::RvizVisualTools::publishYArrow ( const geometry_msgs::PoseStamped &  pose,
colors  color = GREEN,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1254 of file rviz_visual_tools.cpp.

◆ publishYZPlane() [1/2]

bool rviz_visual_tools::RvizVisualTools::publishYZPlane ( const Eigen::Isometry3d &  pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Display the XY plane of a given pose.

Parameters
pose- the position of the plane
color- the color of the plane
scale- the size of the vizualized plane
Returns
true on success

Definition at line 1063 of file rviz_visual_tools.cpp.

◆ publishYZPlane() [2/2]

bool rviz_visual_tools::RvizVisualTools::publishYZPlane ( const geometry_msgs::Pose pose,
colors  color = TRANSLUCENT,
double  scale = 1.0 
)

Definition at line 1068 of file rviz_visual_tools.cpp.

◆ publishZArrow() [1/4]

bool rviz_visual_tools::RvizVisualTools::publishZArrow ( const Eigen::Isometry3d &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0,
std::size_t  id = 0 
)

Display an arrow along the z-axis of a pose.

Parameters
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, if zero, will auto set with scale
Returns
true on success

Definition at line 1262 of file rviz_visual_tools.cpp.

◆ publishZArrow() [2/4]

bool rviz_visual_tools::RvizVisualTools::publishZArrow ( const geometry_msgs::Pose pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1269 of file rviz_visual_tools.cpp.

◆ publishZArrow() [3/4]

bool rviz_visual_tools::RvizVisualTools::publishZArrow ( const geometry_msgs::PoseStamped &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0 
)

Definition at line 1275 of file rviz_visual_tools.cpp.

◆ publishZArrow() [4/4]

bool rviz_visual_tools::RvizVisualTools::publishZArrow ( const geometry_msgs::PoseStamped &  pose,
colors  color = BLUE,
scales  scale = MEDIUM,
double  length = 0.0,
std::size_t  id = 0 
)

Definition at line 1283 of file rviz_visual_tools.cpp.

◆ resetMarkerCounts()

void rviz_visual_tools::RvizVisualTools::resetMarkerCounts ( )

Reset the id's of all published markers so that they overwrite themselves in the future NOTE you may prefer deleteAllMarkers()

Definition at line 84 of file rviz_visual_tools.cpp.

◆ scaleToString()

std::string rviz_visual_tools::RvizVisualTools::scaleToString ( scales  scale)
static

Convert an enum to its string name equivalent.

Definition at line 557 of file rviz_visual_tools.cpp.

◆ setAlpha()

void rviz_visual_tools::RvizVisualTools::setAlpha ( double  alpha)
inline

Change the transparency of all markers published.

Parameters
alpha- value 0 - 1 where 0 is invisible

Definition at line 256 of file rviz_visual_tools.h.

◆ setBaseFrame()

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.

Parameters
nameof frame

Definition at line 343 of file rviz_visual_tools.h.

◆ setGlobalScale()

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 359 of file rviz_visual_tools.h.

◆ setLifetime()

void rviz_visual_tools::RvizVisualTools::setLifetime ( double  lifetime)

Set the lifetime of markers published to rviz.

Parameters
lifetimeseconds of how long to show markers. 0 for inifinity

Definition at line 350 of file rviz_visual_tools.cpp.

◆ setMarkerTopic()

void rviz_visual_tools::RvizVisualTools::setMarkerTopic ( const std::string &  topic)
inline

Set marker array topic.

Definition at line 225 of file rviz_visual_tools.h.

◆ setPsychedelicMode()

void rviz_visual_tools::RvizVisualTools::setPsychedelicMode ( bool  psychedelic_mode = true)
inline

Setter for PsychedelicMode.

Definition at line 1043 of file rviz_visual_tools.h.

◆ slerp()

double rviz_visual_tools::RvizVisualTools::slerp ( double  start,
double  end,
double  range,
double  value 
)
static

Interpolate from [start, end] with value of size steps with current value count.

Returns
interpolated value

Definition at line 608 of file rviz_visual_tools.cpp.

◆ trigger()

bool rviz_visual_tools::RvizVisualTools::trigger ( )

Trigger the publish function to send out all collected markers.

Returns
true on success

Definition at line 862 of file rviz_visual_tools.cpp.

◆ triggerEvery()

bool rviz_visual_tools::RvizVisualTools::triggerEvery ( std::size_t  queueSize)

Trigger the publish function to send out all collected markers IF there are at leats queueSize number of markers ready to be published. a * Warning: when using this in a loop be sure to call trigger() at end of loop in case there are any remainder markers in the queue.

Returns
true on success

Definition at line 853 of file rviz_visual_tools.cpp.

◆ waitForMarkerPub() [1/2]

void rviz_visual_tools::RvizVisualTools::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.

Definition at line 288 of file rviz_visual_tools.cpp.

◆ waitForMarkerPub() [2/2]

void rviz_visual_tools::RvizVisualTools::waitForMarkerPub ( double  wait_time)

Definition at line 294 of file rviz_visual_tools.cpp.

◆ waitForSubscriber()

bool rviz_visual_tools::RvizVisualTools::waitForSubscriber ( const ros::Publisher pub,
double  wait_time = 0.5,
bool  blocking = false 
)

Wait until at least one subscriber connects to a publisher.

Parameters
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
Returns
true on successful connection

Definition at line 300 of file rviz_visual_tools.cpp.

Member Data Documentation

◆ all_rand_colors_

const std::array< colors, 14 > rviz_visual_tools::RvizVisualTools::all_rand_colors_
staticprotected
Initial value:

Definition at line 1106 of file rviz_visual_tools.h.

◆ alpha_

double rviz_visual_tools::RvizVisualTools::alpha_ = 1.0
protected

Definition at line 1082 of file rviz_visual_tools.h.

◆ arrow_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::arrow_marker_
protected

Definition at line 1089 of file rviz_visual_tools.h.

◆ base_frame_

std::string rviz_visual_tools::RvizVisualTools::base_frame_
protected

Definition at line 1074 of file rviz_visual_tools.h.

◆ batch_publishing_enabled_

bool rviz_visual_tools::RvizVisualTools::batch_publishing_enabled_ = true
protected

Definition at line 1080 of file rviz_visual_tools.h.

◆ block_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::block_marker_
protected

Definition at line 1091 of file rviz_visual_tools.h.

◆ cuboid_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::cuboid_marker_
protected

Definition at line 1095 of file rviz_visual_tools.h.

◆ cylinder_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::cylinder_marker_
protected

Definition at line 1092 of file rviz_visual_tools.h.

◆ frame_locking_enabled_

bool rviz_visual_tools::RvizVisualTools::frame_locking_enabled_ = false
protected

Definition at line 1081 of file rviz_visual_tools.h.

◆ global_scale_

double rviz_visual_tools::RvizVisualTools::global_scale_ = 1.0
protected

Definition at line 1083 of file rviz_visual_tools.h.

◆ line_list_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::line_list_marker_
protected

Definition at line 1097 of file rviz_visual_tools.h.

◆ line_strip_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::line_strip_marker_
protected

Definition at line 1096 of file rviz_visual_tools.h.

◆ marker_lifetime_

ros::Duration rviz_visual_tools::RvizVisualTools::marker_lifetime_
protected

Definition at line 1077 of file rviz_visual_tools.h.

◆ marker_topic_

std::string rviz_visual_tools::RvizVisualTools::marker_topic_
protected

Definition at line 1073 of file rviz_visual_tools.h.

◆ markers_

visualization_msgs::MarkerArray rviz_visual_tools::RvizVisualTools::markers_
protected

Definition at line 1086 of file rviz_visual_tools.h.

◆ mesh_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::mesh_marker_
protected

Definition at line 1093 of file rviz_visual_tools.h.

◆ name_

const std::string rviz_visual_tools::RvizVisualTools::name_ = "visual_tools"
staticprotected

Definition at line 1062 of file rviz_visual_tools.h.

◆ nh_

ros::NodeHandle rviz_visual_tools::RvizVisualTools::nh_
protected

Definition at line 1059 of file rviz_visual_tools.h.

◆ psychedelic_mode_

bool rviz_visual_tools::RvizVisualTools::psychedelic_mode_ = false
protected

Definition at line 1103 of file rviz_visual_tools.h.

◆ pub_rviz_markers_

ros::Publisher rviz_visual_tools::RvizVisualTools::pub_rviz_markers_
protected

Definition at line 1068 of file rviz_visual_tools.h.

◆ pub_rviz_markers_connected_

bool rviz_visual_tools::RvizVisualTools::pub_rviz_markers_connected_ = false
protected

Definition at line 1069 of file rviz_visual_tools.h.

◆ pub_rviz_markers_waited_

bool rviz_visual_tools::RvizVisualTools::pub_rviz_markers_waited_ = false
protected

Definition at line 1070 of file rviz_visual_tools.h.

◆ remote_control_

RemoteControlPtr rviz_visual_tools::RvizVisualTools::remote_control_
protected

Definition at line 1065 of file rviz_visual_tools.h.

◆ reset_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::reset_marker_
protected

Definition at line 1099 of file rviz_visual_tools.h.

◆ sphere_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::sphere_marker_
protected

Definition at line 1090 of file rviz_visual_tools.h.

◆ spheres_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::spheres_marker_
protected

Definition at line 1098 of file rviz_visual_tools.h.

◆ text_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::text_marker_
protected

Definition at line 1094 of file rviz_visual_tools.h.

◆ triangle_marker_

visualization_msgs::Marker rviz_visual_tools::RvizVisualTools::triangle_marker_
protected

Definition at line 1100 of file rviz_visual_tools.h.


The documentation for this class was generated from the following files:


rviz_visual_tools
Author(s): Dave Coleman
autogenerated on Mon Feb 28 2022 23:43:06