00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
00040 #define RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
00041
00042 #include <ros/ros.h>
00043
00044
00045 #include <string>
00046 #include <vector>
00047
00048
00049 #include <Eigen/Geometry>
00050
00051
00052 #include <visualization_msgs/Marker.h>
00053 #include <visualization_msgs/MarkerArray.h>
00054
00055
00056 #include <boost/shared_ptr.hpp>
00057
00058
00059 #include <std_msgs/ColorRGBA.h>
00060 #include <graph_msgs/GeometryGraph.h>
00061 #include <geometry_msgs/PoseArray.h>
00062 #include <geometry_msgs/PoseStamped.h>
00063 #include <geometry_msgs/Polygon.h>
00064 #include <trajectory_msgs/JointTrajectory.h>
00065
00066
00067 #include <rviz_visual_tools/deprecation.h>
00068
00069 namespace rviz_visual_tools
00070 {
00071
00072 static const std::string RVIZ_MARKER_TOPIC = "/rviz_visual_tools";
00073 static const double SMALL_SCALE = 0.001;
00074 static const double LARGE_SCALE = 100;
00075
00076
00077 enum colors
00078 {
00079 BLACK = 0,
00080 BROWN = 1,
00081 BLUE = 2,
00082 CYAN = 3,
00083 GREY = 4,
00084 DARK_GREY = 5,
00085 GREEN = 6,
00086 LIME_GREEN = 7,
00087 MAGENTA = 8,
00088 ORANGE = 9,
00089 PURPLE = 10,
00090 RED = 11,
00091 PINK = 12,
00092 WHITE = 13,
00093 YELLOW = 14,
00094 TRANSLUCENT = 15,
00095 TRANSLUCENT_LIGHT = 16,
00096 TRANSLUCENT_DARK = 17,
00097 RAND = 18,
00098 CLEAR = 19,
00099 DEFAULT = 20
00100 };
00101
00102 enum scales
00103 {
00104 XXSMALL,
00105 XSMALL,
00106 SMALL,
00107 REGULAR,
00108 LARGE,
00109 xLARGE,
00110 xxLARGE,
00111 xxxLARGE,
00112 XLARGE,
00113 XXLARGE
00114 };
00115
00119 struct RandomPoseBounds
00120 {
00121 double x_min_, x_max_;
00122 double y_min_, y_max_;
00123 double z_min_, z_max_;
00124 double elevation_min_, elevation_max_;
00125 double azimuth_min_, azimuth_max_;
00126 double angle_min_, angle_max_;
00127
00128 RandomPoseBounds(double x_min = 0.0, double x_max = 1.0, double y_min = 0.0, double y_max = 1.0, double z_min = 0.0,
00129 double z_max = 1.0, double elevation_min = 0.0, double elevation_max = M_PI,
00130 double azimuth_min = 0.0, double azimuth_max = 2 * M_PI, double angle_min = 0.0,
00131 double angle_max = 2 * M_PI)
00132 {
00133 x_min_ = x_min;
00134 x_max_ = x_max;
00135 y_min_ = y_min;
00136 y_max_ = y_max;
00137 z_min_ = z_min;
00138 z_max_ = z_max;
00139 elevation_min_ = elevation_min;
00140 elevation_max_ = elevation_max;
00141 azimuth_min_ = azimuth_min;
00142 azimuth_max_ = azimuth_max;
00143 angle_min_ = angle_min;
00144 angle_max_ = angle_max;
00145 }
00146 };
00147
00151 struct RandomCuboidBounds
00152 {
00153 double cuboid_size_min_, cuboid_size_max_;
00154
00155 explicit RandomCuboidBounds(double cuboid_size_min = 0.02, double cuboid_size_max = 0.15)
00156 {
00157 cuboid_size_min_ = cuboid_size_min;
00158 cuboid_size_max_ = cuboid_size_max;
00159 }
00160 };
00161
00162 class RvizVisualTools
00163 {
00164 private:
00168 void initialize();
00169
00170 public:
00176 explicit RvizVisualTools(const std::string &base_frame, const std::string &marker_topic = RVIZ_MARKER_TOPIC);
00180 ~RvizVisualTools()
00181 {
00182 }
00183
00188 bool deleteAllMarkers();
00189
00194 void resetMarkerCounts();
00195
00200 bool loadRvizMarkers();
00201
00203 void setMarkerTopic(const std::string &topic)
00204 {
00205 marker_topic_ = topic;
00206 }
00207
00213 void loadMarkerPub(bool wait_for_subscriber = false, bool latched=false);
00214
00218 void waitForMarkerPub();
00219
00227 bool waitForSubscriber(const ros::Publisher &pub, const double &wait_time = 0.5, const bool blocking = false);
00228
00233 void setFloorToBaseHeight(double floor_to_base_height);
00234
00239 void setAlpha(double alpha)
00240 {
00241 alpha_ = alpha;
00242 }
00247 void setLifetime(double lifetime);
00248
00253 colors getRandColor();
00254
00260 std_msgs::ColorRGBA getColor(const colors &color);
00261
00266 std_msgs::ColorRGBA createRandColor();
00267
00272 double slerp(double start, double end, double range, double value);
00273
00278 std_msgs::ColorRGBA getColorScale(double value);
00279
00287 geometry_msgs::Vector3 getScale(const scales &scale, bool arrow_scale = false, double marker_scale = 1.0);
00288
00295 Eigen::Affine3d getVectorBetweenPoints(Eigen::Vector3d a, Eigen::Vector3d b);
00296
00303 Eigen::Vector3d getCenterPoint(Eigen::Vector3d a, Eigen::Vector3d b);
00304
00309 const std::string getBaseFrame()
00310 {
00311 return base_frame_;
00312 }
00318 void setBaseFrame(const std::string &base_frame)
00319 {
00320 base_frame_ = base_frame;
00321 loadRvizMarkers();
00322 }
00323
00327 double getGlobalScale()
00328 {
00329 return global_scale_;
00330 }
00334 void setGlobalScale(double global_scale)
00335 {
00336 global_scale_ = global_scale;
00337 }
00343 bool publishMarker(visualization_msgs::Marker &marker);
00344
00350 void enableBatchPublishing(bool enable = true);
00351
00356 bool triggerBatchPublish();
00357
00364 bool triggerBatchPublishAndDisable();
00365
00371 bool publishMarkers(visualization_msgs::MarkerArray &markers);
00372
00380 bool publishCone(const Eigen::Affine3d &pose, double angle, const rviz_visual_tools::colors &color = TRANSLUCENT,
00381 double scale = 1.0);
00382 bool publishCone(const geometry_msgs::Pose &pose, double angle, const rviz_visual_tools::colors &color = TRANSLUCENT,
00383 double scale = 1.0);
00384
00392 bool publishXYPlane(const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00393 double scale = 1.0);
00394 bool publishXYPlane(const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00395 double scale = 1.0);
00396
00404 bool publishXZPlane(const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00405 double scale = 1.0);
00406 bool publishXZPlane(const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00407 double scale = 1.0);
00408
00416 bool publishYZPlane(const Eigen::Affine3d &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00417 double scale = 1.0);
00418 bool publishYZPlane(const geometry_msgs::Pose &pose, const rviz_visual_tools::colors &color = TRANSLUCENT,
00419 double scale = 1.0);
00420
00431 bool publishSphere(const Eigen::Affine3d &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00432 const std::string &ns = "Sphere", const std::size_t &id = 0);
00433 bool publishSphere(const Eigen::Vector3d &point, const colors &color = BLUE, const scales &scale = REGULAR,
00434 const std::string &ns = "Sphere", const std::size_t &id = 0);
00435 bool publishSphere(const Eigen::Vector3d &point, const colors &color, const double scale,
00436 const std::string &ns = "Sphere", const std::size_t &id = 0);
00437 bool publishSphere(const geometry_msgs::Point &point, const colors &color = BLUE, const scales &scale = REGULAR,
00438 const std::string &ns = "Sphere", const std::size_t &id = 0);
00439 bool publishSphere(const geometry_msgs::Pose &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00440 const std::string &ns = "Sphere", const std::size_t &id = 0);
00441 bool publishSphere(const geometry_msgs::Pose &pose, const colors &color, const double scale,
00442 const std::string &ns = "Sphere", const std::size_t &id = 0);
00443 bool publishSphere(const geometry_msgs::Pose &pose, const colors &color, const geometry_msgs::Vector3 scale,
00444 const std::string &ns = "Sphere", const std::size_t &id = 0);
00445 bool publishSphere(const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color,
00446 const geometry_msgs::Vector3 scale, const std::string &ns = "Sphere", const std::size_t &id = 0);
00447 bool publishSphere(const Eigen::Affine3d &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale,
00448 const std::string &ns = "Sphere", const std::size_t &id = 0);
00449 bool publishSphere(const geometry_msgs::PoseStamped &pose, const colors &color, const geometry_msgs::Vector3 scale,
00450 const std::string &ns = "Sphere", const std::size_t &id = 0);
00451
00460 bool publishSpheres(const std::vector<Eigen::Vector3d> &points, const colors &color = BLUE, const double scale = 0.1,
00461 const std::string &ns = "Spheres");
00462 bool publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color = BLUE,
00463 const double scale = 0.1, const std::string &ns = "Spheres");
00464 bool publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color = BLUE,
00465 const scales &scale = REGULAR, const std::string &ns = "Spheres");
00466 bool publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color,
00467 const geometry_msgs::Vector3 &scale, const std::string &ns = "Spheres");
00468
00477 bool publishXArrow(const Eigen::Affine3d &pose, const colors &color = RED, const scales &scale = REGULAR,
00478 double length = 0.1);
00479 bool publishXArrow(const geometry_msgs::Pose &pose, const colors &color = RED, const scales &scale = REGULAR,
00480 double length = 0.1);
00481 bool publishXArrow(const geometry_msgs::PoseStamped &pose, const colors &color = RED, const scales &scale = REGULAR,
00482 double length = 0.1);
00483
00492 bool publishYArrow(const Eigen::Affine3d &pose, const colors &color = GREEN, const scales &scale = REGULAR,
00493 double length = 0.1);
00494 bool publishYArrow(const geometry_msgs::Pose &pose, const colors &color = GREEN, const scales &scale = REGULAR,
00495 double length = 0.1);
00496 bool publishYArrow(const geometry_msgs::PoseStamped &pose, const colors &color = GREEN, const scales &scale = REGULAR,
00497 double length = 0.1);
00498
00507 bool publishZArrow(const Eigen::Affine3d &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00508 double length = 0.1, const std::size_t &id = 0);
00509 bool publishZArrow(const geometry_msgs::Pose &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00510 double length = 0.1);
00511 bool publishZArrow(const geometry_msgs::PoseStamped &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00512 double length = 0.1);
00513 bool publishZArrow(const geometry_msgs::PoseStamped &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00514 double length = 0.1, const std::size_t &id = 0);
00515
00524 bool publishArrow(const Eigen::Affine3d &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00525 double length = 0.1, const std::size_t &id = 0);
00526 bool publishArrow(const geometry_msgs::Pose &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00527 double length = 0.1, const std::size_t &id = 0);
00528 bool publishArrow(const geometry_msgs::PoseStamped &pose, const colors &color = BLUE, const scales &scale = REGULAR,
00529 double length = 0.1, const std::size_t &id = 0);
00530
00538 bool publishCuboid(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color = BLUE);
00539 bool publishCuboid(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const colors &color = BLUE,
00540 const std::string &ns = "Cuboid", const std::size_t &id = 0);
00541
00551 bool publishCuboid(const geometry_msgs::Pose &pose, const double depth, const double width, const double height,
00552 const colors &color = BLUE);
00553 bool publishCuboid(const Eigen::Affine3d &pose, const double depth, const double width, const double height,
00554 const colors &color = BLUE);
00555
00564 bool publishLine(const Eigen::Affine3d &point1, const Eigen::Affine3d &point2, const colors &color = BLUE,
00565 const scales &scale = REGULAR);
00566 bool publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color = BLUE,
00567 const scales &scale = REGULAR);
00568 bool publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color,
00569 const double &radius);
00570 bool publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color,
00571 const scales &scale = REGULAR);
00572 bool publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color,
00573 const double &radius);
00574 bool publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const colors &color = BLUE,
00575 const scales &scale = REGULAR);
00576 bool publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
00577 const std_msgs::ColorRGBA &color, const scales &scale = REGULAR);
00578 bool publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
00579 const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 &scale);
00580
00589 bool publishPath(const std::vector<geometry_msgs::Point> &path, const colors &color = RED,
00590 const scales &scale = REGULAR, const std::string &ns = "Path");
00591
00592 bool publishPath(const std::vector<Eigen::Vector3d> &path, const colors &color = RED, const double radius = 0.01,
00593 const std::string &ns = "Path");
00594
00603 bool publishPolygon(const geometry_msgs::Polygon &polygon, const colors &color = RED, const scales &scale = REGULAR,
00604 const std::string &ns = "Polygon");
00605
00614 bool publishBlock(const geometry_msgs::Pose &pose, const colors &color = BLUE, const double &block_size = 0.1);
00615 RVIZ_VISUAL_TOOLS_DEPRECATED
00616 bool publishBlock(const Eigen::Affine3d &pose, const colors &color = BLUE, const double &block_size = 0.1);
00617
00630 bool publishWireframeCuboid(const Eigen::Affine3d &pose, double depth, double width, double height,
00631 const rviz_visual_tools::colors &color = BLUE, const std::string &ns = "Wireframe Cuboid",
00632 const std::size_t &id = 0);
00633
00644 bool publishWireframeCuboid(const Eigen::Affine3d &pose, const Eigen::Vector3d &min_point,
00645 const Eigen::Vector3d &max_point, const rviz_visual_tools::colors &color = BLUE,
00646 const std::string &ns = "Wireframe Cuboid", const std::size_t &id = 0);
00647
00657 bool publishWireframeRectangle(const Eigen::Affine3d &pose, const double &height, const double &width,
00658 const colors &color = BLUE, const scales &scale = REGULAR, const std::size_t &id = 0);
00659 bool publishWireframeRectangle(const Eigen::Affine3d &pose, const Eigen::Vector3d &p1, const Eigen::Vector3d &p2,
00660 const Eigen::Vector3d &p3, const Eigen::Vector3d &p4, const colors &color,
00661 const scales &scale);
00670 bool publishAxisLabeled(const Eigen::Affine3d &pose, const std::string &label, const scales &scale = SMALL,
00671 const colors &color = WHITE);
00672 bool publishAxisLabeled(const geometry_msgs::Pose &pose, const std::string &label, const scales &scale = SMALL,
00673 const colors &color = WHITE);
00674
00682 bool publishAxis(const geometry_msgs::Pose &pose, double length = 0.1, double radius = 0.01,
00683 const std::string &ns = "Axis");
00684 bool publishAxis(const Eigen::Affine3d &pose, double length = 0.1, double radius = 0.01,
00685 const std::string &ns = "Axis");
00686
00695 bool publishCylinder(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color = BLUE,
00696 double radius = 0.01, const std::string &ns = "Cylinder");
00697 bool publishCylinder(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color,
00698 double radius = 0.01, const std::string &ns = "Cylinder");
00699
00708 bool publishCylinder(const Eigen::Affine3d &pose, const colors &color = BLUE, double height = 0.1,
00709 double radius = 0.01, const std::string &ns = "Cylinder");
00710 bool publishCylinder(const geometry_msgs::Pose &pose, const colors &color = BLUE, double height = 0.1,
00711 double radius = 0.01, const std::string &ns = "Cylinder");
00712 bool publishCylinder(const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, double height = 0.1,
00713 double radius = 0.01, const std::string &ns = "Cylinder");
00714
00726 bool publishMesh(const Eigen::Affine3d &pose, const std::string &file_name, const colors &color = CLEAR,
00727 double scale = 1, const std::string &ns = "mesh", const std::size_t &id = 0);
00728 bool publishMesh(const geometry_msgs::Pose &pose, const std::string &file_name, const colors &color = CLEAR,
00729 double scale = 1, const std::string &ns = "mesh", const std::size_t &id = 0);
00730
00738 bool publishGraph(const graph_msgs::GeometryGraph &graph, const colors &color, double radius);
00739
00749 bool publishText(const Eigen::Affine3d &pose, const std::string &text, const colors &color = WHITE,
00750 const scales &scale = REGULAR, bool static_id = true);
00751 bool publishText(const Eigen::Affine3d &pose, const std::string &text, const colors &color,
00752 const geometry_msgs::Vector3 scale, bool static_id = true);
00753 bool publishText(const geometry_msgs::Pose &pose, const std::string &text, const colors &color = WHITE,
00754 const scales &scale = REGULAR, bool static_id = true);
00755 bool publishText(const geometry_msgs::Pose &pose, const std::string &text, const colors &color,
00756 const geometry_msgs::Vector3 scale, bool static_id = true);
00757
00762 RVIZ_VISUAL_TOOLS_DEPRECATED
00763 bool publishTests();
00764
00771 geometry_msgs::Pose convertPose(const Eigen::Affine3d &pose);
00772
00778 static void convertPoseSafe(const Eigen::Affine3d &pose, geometry_msgs::Pose &pose_msg);
00779
00786 Eigen::Affine3d convertPose(const geometry_msgs::Pose &pose);
00787
00794 Eigen::Affine3d convertPoint32ToPose(const geometry_msgs::Point32 &point);
00795
00799 geometry_msgs::Pose convertPointToPose(const geometry_msgs::Point &point);
00800 Eigen::Affine3d convertPointToPose(const Eigen::Vector3d &point);
00801
00808 geometry_msgs::Point convertPoseToPoint(const Eigen::Affine3d &pose);
00809
00816 Eigen::Vector3d convertPoint(const geometry_msgs::Point &point);
00817
00824 Eigen::Vector3d convertPoint32(const geometry_msgs::Point32 &point);
00825
00832 geometry_msgs::Point32 convertPoint32(const Eigen::Vector3d &point);
00833
00840 geometry_msgs::Point convertPoint(const geometry_msgs::Vector3 &point);
00841
00848 geometry_msgs::Point convertPoint(const Eigen::Vector3d &point);
00849
00855 static Eigen::Affine3d convertFromXYZRPY(const double &x, const double &y, const double &z, const double &roll,
00856 const double &pitch, const double &yaw);
00857 static Eigen::Affine3d convertFromXYZRPY(std::vector<double> transform6);
00858
00865 static void convertToXYZRPY(const Eigen::Affine3d &pose, std::vector<double> &xyzrpy);
00866 static void convertToXYZRPY(const Eigen::Affine3d &pose, double &x, double &y, double &z, double &roll, double &pitch,
00867 double &yaw);
00873 void generateRandomPose(geometry_msgs::Pose &pose, RandomPoseBounds pose_bounds = RandomPoseBounds());
00874 void generateRandomPose(Eigen::Affine3d &pose, RandomPoseBounds pose_bounds = RandomPoseBounds());
00875
00879 void generateRandomCuboid(geometry_msgs::Pose &cuboid_pose, double &depth, double &width, double &height,
00880 RandomPoseBounds pose_bounds = RandomPoseBounds(),
00881 RandomCuboidBounds cuboid_bounds = RandomCuboidBounds());
00882
00887 void generateEmptyPose(geometry_msgs::Pose &pose);
00888
00896 bool posesEqual(const Eigen::Affine3d &pose1, const Eigen::Affine3d &pose2, const double &threshold = 0.000001);
00897
00901 static double dRand(double min, double max);
00902 static float fRand(float min, float max);
00903 static int iRand(int min, int max);
00904
00908 static void printTransform(const Eigen::Affine3d &transform);
00909
00913 static void printTransformRPY(const Eigen::Affine3d &transform);
00914
00916 const bool &getPsychedelicMode() const
00917 {
00918 return psychedelic_mode_;
00919 }
00920
00922 void setPsychedelicMode(const bool &psychedelic_mode = true)
00923 {
00924 psychedelic_mode_ = psychedelic_mode;
00925 }
00926
00927 protected:
00931 void enableInternalBatchPublishing(bool enable);
00932
00939 bool triggerInternalBatchPublishAndDisable();
00940
00941
00942 ros::NodeHandle nh_;
00943
00944
00945 std::string name_;
00946
00947
00948 ros::Publisher pub_rviz_markers_;
00949 bool pub_rviz_markers_connected_;
00950 bool pub_rviz_markers_waited_;
00951
00952
00953 std::string marker_topic_;
00954 std::string base_frame_;
00955
00956
00957 ros::Duration marker_lifetime_;
00958
00959
00960 bool batch_publishing_enabled_;
00961 bool internal_batch_publishing_enabled_;
00962
00963 double alpha_;
00964 double global_scale_;
00965
00966
00967 visualization_msgs::MarkerArray markers_;
00968
00969
00970 visualization_msgs::Marker arrow_marker_;
00971 visualization_msgs::Marker sphere_marker_;
00972 visualization_msgs::Marker block_marker_;
00973 visualization_msgs::Marker cylinder_marker_;
00974 visualization_msgs::Marker mesh_marker_;
00975 visualization_msgs::Marker text_marker_;
00976 visualization_msgs::Marker cuboid_marker_;
00977 visualization_msgs::Marker line_strip_marker_;
00978 visualization_msgs::Marker line_list_marker_;
00979 visualization_msgs::Marker spheres_marker_;
00980 visualization_msgs::Marker reset_marker_;
00981 visualization_msgs::Marker triangle_marker_;
00982
00983
00984 geometry_msgs::Pose shared_pose_msg_;
00985 geometry_msgs::Point shared_point_msg_;
00986 geometry_msgs::Point32 shared_point32_msg_;
00987 Eigen::Affine3d shared_pose_eigen_;
00988 Eigen::Vector3d shared_point_eigen_;
00989
00990
00991 bool psychedelic_mode_;
00992 };
00993
00994 typedef boost::shared_ptr<RvizVisualTools> RvizVisualToolsPtr;
00995 typedef boost::shared_ptr<const RvizVisualTools> RvizVisualToolsConstPtr;
00996
00997 }
00998
00999 #endif // RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H