#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... | |
RemoteControlPtr & | getRemoteControl () |
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... | |
Definition at line 184 of file rviz_visual_tools.h.
|
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 |
nh | - optional ros node handle - defaults to "~" |
Definition at line 64 of file rviz_visual_tools.cpp.
|
inline |
Deconstructor.
Definition at line 203 of file rviz_visual_tools.h.
|
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.
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.
|
static |
Definition at line 2574 of file rviz_visual_tools.cpp.
|
static |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.
point |
Definition at line 2499 of file rviz_visual_tools.cpp.
|
static |
Convert a Vector3 to a geometry_msg Point Note: Not thread safe but very convenient.
point |
Definition at line 2526 of file rviz_visual_tools.cpp.
|
static |
Convert a Eigen point to a geometry_msg Point Note: Not thread safe but very convenient.
point |
Definition at line 2535 of file rviz_visual_tools.cpp.
|
static |
Convert a geometry_msg point to an Eigen point Note: Not thread safe but very convenient.
point |
Definition at line 2508 of file rviz_visual_tools.cpp.
|
static |
Convert an Eigen point to a 32 bit geometry_msg point Note: Not thread safe but very convenient.
point |
Definition at line 2517 of file rviz_visual_tools.cpp.
|
static |
Convert a geometry_msg point (32bit) to an Eigen pose Note: Not thread safe but very convenient.
pose |
Definition at line 2463 of file rviz_visual_tools.cpp.
|
static |
Add an identity rotation matrix to make a point have a full pose.
Definition at line 2473 of file rviz_visual_tools.cpp.
|
static |
Definition at line 2484 of file rviz_visual_tools.cpp.
|
static |
Convert an Eigen pose to a geometry_msg pose.
pose |
Definition at line 2439 of file rviz_visual_tools.cpp.
|
static |
Convert a geometry_msg pose to an Eigen pose Note: Not thread safe but very convenient.
ROS | msg pose |
Definition at line 2451 of file rviz_visual_tools.cpp.
|
static |
Convert an Eigen pose to a geometry_msg pose - thread safe.
Eigen | pose - input |
ROS | msg pose - output |
Definition at line 2446 of file rviz_visual_tools.cpp.
|
static |
Convert a geometry_msg pose to an Eigen pose - thread safe.
ROS | msg pose - input |
Eigen | pose - output |
Definition at line 2458 of file rviz_visual_tools.cpp.
|
static |
Convert an Eigen pose to a geometry_msg point Note: Not thread safe but very convenient.
pose |
Definition at line 2492 of file rviz_visual_tools.cpp.
|
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 2586 of file rviz_visual_tools.cpp.
|
static |
Definition at line 2592 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::createRandColor | ( | ) | const |
Create a random color that is not too light.
Definition at line 579 of file rviz_visual_tools.cpp.
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.
|
static |
Get random between min and max.
Definition at line 2719 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 trigger() is called.
Definition at line 843 of file rviz_visual_tools.cpp.
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.
|
static |
Definition at line 2725 of file rviz_visual_tools.cpp.
|
static |
Create a pose of position (0,0,0) and quaternion (0,0,0,1)
Pose | to fill in |
Definition at line 2674 of file rviz_visual_tools.cpp.
|
static |
Create a random rectangular cuboid of some shape.
Definition at line 2613 of file rviz_visual_tools.cpp.
|
static |
Create a random pose within bounds of random_pose_bounds_.
Pose | to fill in options bounds on the pose to generate |
Definition at line 2606 of file rviz_visual_tools.cpp.
|
static |
Definition at line 2626 of file rviz_visual_tools.cpp.
|
inline |
Eigen::Vector3d rviz_visual_tools::RvizVisualTools::getCenterPoint | ( | const Eigen::Vector3d & | a, |
const Eigen::Vector3d & | b | ||
) | const |
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 712 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColor | ( | colors | color | ) | const |
Get the RGB value of standard colors.
color | - an enum pre-defined name of a color |
Definition at line 371 of file rviz_visual_tools.cpp.
std_msgs::ColorRGBA rviz_visual_tools::RvizVisualTools::getColorScale | ( | double | value | ) | const |
Convert a value from [0,1] to a color Green->Red.
Definition at line 613 of file rviz_visual_tools.cpp.
|
inline |
Getter for the global scale used for changing size of all markers.
Definition at line 352 of file rviz_visual_tools.h.
|
static |
Definition at line 2688 of file rviz_visual_tools.cpp.
|
inline |
Getter for PsychedelicMode.
Definition at line 1037 of file rviz_visual_tools.h.
|
static |
Get a random color from the list of hardcoded enum color types.
Definition at line 365 of file rviz_visual_tools.cpp.
RemoteControlPtr & rviz_visual_tools::RvizVisualTools::getRemoteControl | ( | ) |
Ability to load remote control on the fly.
Definition at line 2776 of file rviz_visual_tools.cpp.
geometry_msgs::Vector3 rviz_visual_tools::RvizVisualTools::getScale | ( | scales | scale, |
double | marker_scale = 1.0 |
||
) | const |
Get the rviz marker scale of standard sizes.
scale | - an enum pre-defined name of a size |
marker_scale | - amount to scale the scale for accounting for different types of markers |
Definition at line 660 of file rviz_visual_tools.cpp.
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.
point | a - x,y,z in space of a point |
point | b - x,y,z in space of a point |
Definition at line 721 of file rviz_visual_tools.cpp.
|
private |
Shared function for initilization by constructors.
Definition at line 70 of file rviz_visual_tools.cpp.
|
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.
|
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.
|
static |
Definition at line 2731 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 271 of file rviz_visual_tools.cpp.
void rviz_visual_tools::RvizVisualTools::loadRemoteControl | ( | ) |
Pre-load remote control.
Definition at line 2785 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::loadRvizMarkers | ( | ) |
Pre-load rviz markers for better efficiency.
Definition at line 99 of file rviz_visual_tools.cpp.
|
static |
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 2704 of file rviz_visual_tools.cpp.
|
static |
Display in the console a transform in quaternions.
Definition at line 2748 of file rviz_visual_tools.cpp.
|
static |
Display in the console a transform with full 3x3 rotation matrix.
Definition at line 2764 of file rviz_visual_tools.cpp.
|
static |
Display in the console a transform in roll pitch yaw.
Definition at line 2756 of file rviz_visual_tools.cpp.
|
static |
Display in the console the x,y,z values of a point.
Definition at line 2743 of file rviz_visual_tools.cpp.
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.
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.
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 |
Definition at line 1292 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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 |
Definition at line 1421 of file rviz_visual_tools.cpp.
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.
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.
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.
|
private |
Display a red/green/blue coordinate axis - the 'internal' version does not do a batch publish.
pose | - the location to publish the marker with respect to the base frame |
length | - geometry of cylinder |
radius | - geometry of cylinder |
ns | - namespace |
Definition at line 1447 of file rviz_visual_tools.cpp.
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.
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 1401 of file rviz_visual_tools.cpp.
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.
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.
path | - the location to publish each marker with respect to the base frame |
length | - geometry of cylinder |
radius | - geometry of cylinder |
ns | - namespace |
Definition at line 1470 of file rviz_visual_tools.cpp.
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.
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.
pose | - the location and orientation of the cone |
color | - color of the cone |
scale | - size of the cone |
Definition at line 925 of file rviz_visual_tools.cpp.
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.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
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 1640 of file rviz_visual_tools.cpp.
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.
bool rviz_visual_tools::RvizVisualTools::publishCuboid | ( | const geometry_msgs::Pose & | pose, |
double | depth, | ||
double | width, | ||
double | height, | ||
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 1699 of file rviz_visual_tools.cpp.
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.
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.
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 1494 of file rviz_visual_tools.cpp.
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.
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.
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.
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 1529 of file rviz_visual_tools.cpp.
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.
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.
bool rviz_visual_tools::RvizVisualTools::publishGraph | ( | const graph_msgs::GeometryGraph & | graph, |
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 1608 of file rviz_visual_tools.cpp.
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.
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 1740 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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.
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.
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.
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.
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 |
Definition at line 1807 of file rviz_visual_tools.cpp.
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.
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.
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 1864 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 828 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 880 of file rviz_visual_tools.cpp.
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.
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 1564 of file rviz_visual_tools.cpp.
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.
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.
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 |
Definition at line 1898 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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.
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.
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.
path | - a series of points to connect with cylinders |
colors | - a series of colors |
radius | - the radius of the cylinders |
ns | - namespace of marker |
Definition at line 1982 of file rviz_visual_tools.cpp.
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.
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.
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 2032 of file rviz_visual_tools.cpp.
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.
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 1109 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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 2283 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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.
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 2351 of file rviz_visual_tools.cpp.
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.
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.
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 2388 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
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 2056 of file rviz_visual_tools.cpp.
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.
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 2065 of file rviz_visual_tools.cpp.
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.
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 2172 of file rviz_visual_tools.cpp.
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.
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.
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 |
Definition at line 1227 of file rviz_visual_tools.cpp.
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.
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.
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.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 971 of file rviz_visual_tools.cpp.
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.
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.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 1017 of file rviz_visual_tools.cpp.
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.
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.
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 |
Definition at line 1242 of file rviz_visual_tools.cpp.
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.
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.
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.
pose | - the position of the plane |
color | - the color of the plane |
scale | - the size of the vizualized plane |
Definition at line 1063 of file rviz_visual_tools.cpp.
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.
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.
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 |
Definition at line 1262 of file rviz_visual_tools.cpp.
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.
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.
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.
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.
|
static |
Convert an enum to its string name equivalent.
Definition at line 557 of file rviz_visual_tools.cpp.
|
inline |
Change the transparency of all markers published.
alpha | - value 0 - 1 where 0 is invisible |
Definition at line 256 of file rviz_visual_tools.h.
|
inline |
Change the global base frame Note: this might reset all your current markers.
name | of frame |
Definition at line 343 of file rviz_visual_tools.h.
|
inline |
Setter for the global scale used for changing size of all markers.
Definition at line 359 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 350 of file rviz_visual_tools.cpp.
|
inline |
Set marker array topic.
Definition at line 225 of file rviz_visual_tools.h.
|
inline |
Setter for PsychedelicMode.
Definition at line 1043 of file rviz_visual_tools.h.
|
static |
Interpolate from [start, end] with value of size steps with current value count.
Definition at line 608 of file rviz_visual_tools.cpp.
bool rviz_visual_tools::RvizVisualTools::trigger | ( | ) |
Trigger the publish function to send out all collected markers.
Definition at line 862 of file rviz_visual_tools.cpp.
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.
Definition at line 853 of file rviz_visual_tools.cpp.
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.
void rviz_visual_tools::RvizVisualTools::waitForMarkerPub | ( | double | wait_time | ) |
Definition at line 294 of file rviz_visual_tools.cpp.
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.
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 300 of file rviz_visual_tools.cpp.
|
staticprotected |
|
protected |
Definition at line 1082 of file rviz_visual_tools.h.
|
protected |
Definition at line 1089 of file rviz_visual_tools.h.
|
protected |
Definition at line 1074 of file rviz_visual_tools.h.
|
protected |
Definition at line 1080 of file rviz_visual_tools.h.
|
protected |
Definition at line 1091 of file rviz_visual_tools.h.
|
protected |
Definition at line 1095 of file rviz_visual_tools.h.
|
protected |
Definition at line 1092 of file rviz_visual_tools.h.
|
protected |
Definition at line 1081 of file rviz_visual_tools.h.
|
protected |
Definition at line 1083 of file rviz_visual_tools.h.
|
protected |
Definition at line 1097 of file rviz_visual_tools.h.
|
protected |
Definition at line 1096 of file rviz_visual_tools.h.
|
protected |
Definition at line 1077 of file rviz_visual_tools.h.
|
protected |
Definition at line 1073 of file rviz_visual_tools.h.
|
protected |
Definition at line 1086 of file rviz_visual_tools.h.
|
protected |
Definition at line 1093 of file rviz_visual_tools.h.
|
staticprotected |
Definition at line 1062 of file rviz_visual_tools.h.
|
protected |
Definition at line 1059 of file rviz_visual_tools.h.
|
protected |
Definition at line 1103 of file rviz_visual_tools.h.
|
protected |
Definition at line 1068 of file rviz_visual_tools.h.
|
protected |
Definition at line 1069 of file rviz_visual_tools.h.
|
protected |
Definition at line 1070 of file rviz_visual_tools.h.
|
protected |
Definition at line 1065 of file rviz_visual_tools.h.
|
protected |
Definition at line 1099 of file rviz_visual_tools.h.
|
protected |
Definition at line 1090 of file rviz_visual_tools.h.
|
protected |
Definition at line 1098 of file rviz_visual_tools.h.
|
protected |
Definition at line 1094 of file rviz_visual_tools.h.
|
protected |
Definition at line 1100 of file rviz_visual_tools.h.