rviz_visual_tools.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, PickNik Consulting
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman <dave@picknik.ai>, Andy McEvoy
36  Desc: Helper functions for displaying basic shape markers in Rviz
37 */
38 
39 #ifndef RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
40 #define RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
41 
42 #include <ros/ros.h>
43 
44 // C++
45 #include <string>
46 #include <vector>
47 
48 // Eigen
49 #include <Eigen/Geometry>
51 
52 // Rviz
53 #include <visualization_msgs/Marker.h>
54 #include <visualization_msgs/MarkerArray.h>
55 
56 // Boost
57 #include <boost/shared_ptr.hpp>
58 
59 // Messages
60 #include <std_msgs/ColorRGBA.h>
61 #include <graph_msgs/GeometryGraph.h>
62 #include <geometry_msgs/PoseArray.h>
63 #include <geometry_msgs/PoseStamped.h>
64 #include <geometry_msgs/Polygon.h>
65 #include <trajectory_msgs/JointTrajectory.h>
66 
67 // rviz_visual_tools
70 
71 // Import/export for windows dll's and visibility for gcc shared libraries.
72 
73 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
74  #ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll
75  #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT
76  #else // we are using shared lib/dll
77  #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT
78  #endif
79 #else // ros is being built around static libraries
80  #define RVIZ_VISUAL_TOOLS_DECL
81 #endif
82 
83 namespace rviz_visual_tools
84 {
85 // Default constants
86 static const std::string RVIZ_MARKER_TOPIC = "/rviz_visual_tools";
87 static const double SMALL_SCALE = 0.001;
88 static const double LARGE_SCALE = 100;
89 
90 // Note: when adding new colors to colors, also add them to getRandColor() function
91 enum colors
92 {
93  BLACK = 0,
94  BROWN = 1,
95  BLUE = 2,
96  CYAN = 3,
97  GREY = 4,
98  DARK_GREY = 5,
99  GREEN = 6,
101  MAGENTA = 8,
102  ORANGE = 9,
103  PURPLE = 10,
104  RED = 11,
105  PINK = 12,
106  WHITE = 13,
107  YELLOW = 14,
111  RAND = 18,
112  CLEAR = 19,
113  DEFAULT = 20 // i.e. 'do not change default color'
114 };
115 
116 enum scales
117 {
119  XXXSMALL = 2,
120  XXSMALL = 3,
121  XSMALL = 4,
122  SMALL = 5,
123  MEDIUM = 6, // same as REGULAR
124  LARGE = 7,
125  XLARGE = 8,
126  XXLARGE = 9,
127  XXXLARGE = 10,
128  XXXXLARGE = 11,
129 };
130 
132 {
133  XYZ = 0,
134  ZYX, // This is the ROS standard: http://www.ros.org/reps/rep-0103.html
136 };
137 
142 {
143  double x_min_, x_max_;
144  double y_min_, y_max_;
145  double z_min_, z_max_;
149 
150  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,
151  double z_max = 1.0, double elevation_min = 0.0, double elevation_max = M_PI,
152  double azimuth_min = 0.0, double azimuth_max = 2 * M_PI, double angle_min = 0.0,
153  double angle_max = 2 * M_PI)
154  {
155  x_min_ = x_min;
156  x_max_ = x_max;
157  y_min_ = y_min;
158  y_max_ = y_max;
159  z_min_ = z_min;
160  z_max_ = z_max;
161  elevation_min_ = elevation_min;
162  elevation_max_ = elevation_max;
163  azimuth_min_ = azimuth_min;
164  azimuth_max_ = azimuth_max;
165  angle_min_ = angle_min;
166  angle_max_ = angle_max;
167  }
168 };
169 
174 {
175  double cuboid_size_min_, cuboid_size_max_;
176 
177  explicit RandomCuboidBounds(double cuboid_size_min = 0.02, double cuboid_size_max = 0.15)
178  {
179  cuboid_size_min_ = cuboid_size_min;
180  cuboid_size_max_ = cuboid_size_max;
181  }
182 };
183 
185 {
186 private:
190  void initialize();
191 
192 public:
199  explicit RvizVisualTools(std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC, ros::NodeHandle nh = ros::NodeHandle("~"));
204  {
205  }
206 
210  bool deleteAllMarkers();
211 
216  void resetMarkerCounts();
217 
222  bool loadRvizMarkers();
223 
225  void setMarkerTopic(const std::string& topic)
226  {
227  marker_topic_ = topic;
228  }
229 
235  void loadMarkerPub(bool wait_for_subscriber = false, bool latched = false);
236 
240  void waitForMarkerPub();
241  void waitForMarkerPub(double wait_time);
242 
250  bool waitForSubscriber(const ros::Publisher& pub, double wait_time = 0.5, bool blocking = false);
251 
256  void setAlpha(double alpha)
257  {
258  alpha_ = alpha;
259  }
264  void setLifetime(double lifetime);
265 
270  static colors getRandColor();
271 
277  std_msgs::ColorRGBA getColor(colors color) const;
278 
280  static colors intToRvizColor(std::size_t color);
281 
283  static rviz_visual_tools::scales intToRvizScale(std::size_t scale);
284 
286  static std::string scaleToString(scales scale);
287 
292  std_msgs::ColorRGBA createRandColor() const;
293 
298  static double slerp(double start, double end, double range, double value);
299 
304  std_msgs::ColorRGBA getColorScale(double value) const;
305 
312  geometry_msgs::Vector3 getScale(scales scale, double marker_scale = 1.0) const;
313 
320  Eigen::Isometry3d getVectorBetweenPoints(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const;
321 
328  Eigen::Vector3d getCenterPoint(const Eigen::Vector3d& a, const Eigen::Vector3d& b) const;
329 
334  const std::string getBaseFrame() const
335  {
336  return base_frame_;
337  }
343  void setBaseFrame(const std::string& base_frame)
344  {
345  base_frame_ = base_frame;
346  loadRvizMarkers();
347  }
348 
352  double getGlobalScale() const
353  {
354  return global_scale_;
355  }
359  void setGlobalScale(double global_scale)
360  {
361  global_scale_ = global_scale;
362  }
368  bool publishMarker(visualization_msgs::Marker& marker);
369 
375  void enableBatchPublishing(bool enable = true);
376 
381  void enableFrameLocking(bool enable = true);
382 
390  bool triggerEvery(std::size_t queueSize);
391 
396  bool trigger();
397 
403  bool publishMarkers(visualization_msgs::MarkerArray& markers);
404 
412  bool publishCone(const Eigen::Isometry3d& pose, double angle, colors color = TRANSLUCENT, double scale = 1.0);
413  bool publishCone(const geometry_msgs::Pose& pose, double angle, colors color = TRANSLUCENT, double scale = 1.0);
414 
422  bool publishXYPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0);
423  bool publishXYPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0);
424 
432  bool publishXZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0);
433  bool publishXZPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0);
434 
442  bool publishYZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, double scale = 1.0);
443  bool publishYZPlane(const geometry_msgs::Pose& pose, colors color = TRANSLUCENT, double scale = 1.0);
444 
455  bool publishSphere(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM,
456  const std::string& ns = "Sphere", std::size_t id = 0);
457  bool publishSphere(const Eigen::Vector3d& point, colors color = BLUE, scales scale = MEDIUM,
458  const std::string& ns = "Sphere", std::size_t id = 0);
459  bool publishSphere(const Eigen::Vector3d& point, colors color, double scale, const std::string& ns = "Sphere",
460  std::size_t id = 0);
461  bool publishSphere(const geometry_msgs::Point& point, colors color = BLUE, scales scale = MEDIUM,
462  const std::string& ns = "Sphere", std::size_t id = 0);
463  bool publishSphere(const geometry_msgs::Pose& pose, colors color = BLUE, scales scale = MEDIUM,
464  const std::string& ns = "Sphere", std::size_t id = 0);
465  bool publishSphere(const geometry_msgs::Pose& pose, colors color, double scale, const std::string& ns = "Sphere",
466  std::size_t id = 0);
467  bool publishSphere(const geometry_msgs::Pose& pose, colors color, const geometry_msgs::Vector3 scale,
468  const std::string& ns = "Sphere", std::size_t id = 0);
469  bool publishSphere(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color,
470  const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0);
471  bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
472  const std::string& ns = "Sphere", std::size_t id = 0);
473  bool publishSphere(const Eigen::Vector3d& point, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
474  const std::string& ns = "Sphere", std::size_t id = 0);
475  bool publishSphere(const geometry_msgs::PoseStamped& pose, colors color, const geometry_msgs::Vector3 scale,
476  const std::string& ns = "Sphere", std::size_t id = 0);
477 
486  bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color = BLUE, scales scale = MEDIUM,
487  const std::string& ns = "Spheres");
488  bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color, double scale = 0.1,
489  const std::string& ns = "Spheres");
490  bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color = BLUE, scales scale = MEDIUM,
491  const std::string& ns = "Spheres");
492  bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color = BLUE, double scale = 0.1,
493  const std::string& ns = "Spheres");
494  bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color,
495  const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres");
496 
505  bool publishSpheres(const EigenSTL::vector_Vector3d& points, const std::vector<colors>& colors, scales scale = MEDIUM,
506  const std::string& ns = "Spheres");
507  bool publishSpheres(const std::vector<geometry_msgs::Point>& points, const std::vector<std_msgs::ColorRGBA>& colors,
508  const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres");
509 
518  bool publishXArrow(const Eigen::Isometry3d& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0);
519  bool publishXArrow(const geometry_msgs::Pose& pose, colors color = RED, scales scale = MEDIUM, double length = 0.0);
520  bool publishXArrow(const geometry_msgs::PoseStamped& pose, colors color = RED, scales scale = MEDIUM,
521  double length = 0.0);
522 
531  bool publishYArrow(const Eigen::Isometry3d& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0);
532  bool publishYArrow(const geometry_msgs::Pose& pose, colors color = GREEN, scales scale = MEDIUM, double length = 0.0);
533  bool publishYArrow(const geometry_msgs::PoseStamped& pose, colors color = GREEN, scales scale = MEDIUM,
534  double length = 0.0);
535 
544  bool publishZArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0,
545  std::size_t id = 0);
546  bool publishZArrow(const geometry_msgs::Pose& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0);
547  bool publishZArrow(const geometry_msgs::PoseStamped& pose, colors color = BLUE, scales scale = MEDIUM,
548  double length = 0.0);
549  bool publishZArrow(const geometry_msgs::PoseStamped& pose, colors color = BLUE, scales scale = MEDIUM,
550  double length = 0.0, std::size_t id = 0);
551 
562  bool publishArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0,
563  std::size_t id = 0);
564  bool publishArrow(const geometry_msgs::Pose& pose, colors color = BLUE, scales scale = MEDIUM, double length = 0.0,
565  std::size_t id = 0);
566  bool publishArrow(const geometry_msgs::PoseStamped& pose, colors color = BLUE, scales scale = MEDIUM,
567  double length = 0.0, std::size_t id = 0);
568  bool publishArrow(const geometry_msgs::Point& start, const geometry_msgs::Point& end, colors color = BLUE,
569  scales scale = MEDIUM, std::size_t id = 0);
570 
578  bool publishCuboid(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color = BLUE);
579  bool publishCuboid(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2, colors color = BLUE,
580  const std::string& ns = "Cuboid", std::size_t id = 0);
581 
591  bool publishCuboid(const geometry_msgs::Pose& pose, double depth, double width, double height, colors color = BLUE);
592  bool publishCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, colors color = BLUE);
593 
602  bool publishLine(const Eigen::Isometry3d& point1, const Eigen::Isometry3d& point2, colors color = BLUE,
603  scales scale = MEDIUM);
604  bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color = BLUE,
605  scales scale = MEDIUM);
606  bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color, double radius);
607  bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::ColorRGBA& color,
608  scales scale = MEDIUM);
609  bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::ColorRGBA& color,
610  double radius);
611  bool publishLine(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2, colors color = BLUE,
612  scales scale = MEDIUM);
613  bool publishLine(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2,
614  const std_msgs::ColorRGBA& color, scales scale = MEDIUM);
615  bool publishLine(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2,
616  const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3& scale);
617 
626  bool publishLines(const EigenSTL::vector_Vector3d& aPoints, const EigenSTL::vector_Vector3d& bPoints,
627  const std::vector<colors>& colors, scales scale = MEDIUM);
628  bool publishLines(const std::vector<geometry_msgs::Point>& aPoints, const std::vector<geometry_msgs::Point>& bPoints,
629  const std::vector<std_msgs::ColorRGBA>& colors, const geometry_msgs::Vector3& scale);
630 
639  bool publishLineStrip(const std::vector<geometry_msgs::Point>& path, colors color = RED, scales scale = MEDIUM,
640  const std::string& ns = "Path");
641 
650  bool publishPath(const std::vector<geometry_msgs::Pose>& path, colors color = RED, scales scale = MEDIUM,
651  const std::string& ns = "Path");
652  bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color, scales scale,
653  const std::string& ns = "Path");
654  bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale,
655  const std::string& ns = "Path");
656  bool publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale,
657  const std::string& ns = "Path");
658  bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color = RED, double radius = 0.01,
659  const std::string& ns = "Path");
660  bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01,
661  const std::string& ns = "Path");
662  bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color = RED, double radius = 0.01,
663  const std::string& ns = "Path");
664 
674  bool publishPath(const EigenSTL::vector_Vector3d& path, const std::vector<colors>& colors, double radius = 0.01,
675  const std::string& ns = "Path");
676 
677  bool publishPath(const EigenSTL::vector_Vector3d& path, const std::vector<std_msgs::ColorRGBA>& colors, double radius,
678  const std::string& ns = "Path");
679 
688  bool publishPolygon(const geometry_msgs::Polygon& polygon, colors color = RED, scales scale = MEDIUM,
689  const std::string& ns = "Polygon");
690 
703  bool publishWireframeCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height,
704  colors color = BLUE, const std::string& ns = "Wireframe Cuboid", std::size_t id = 0);
705 
716  bool publishWireframeCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& min_point,
717  const Eigen::Vector3d& max_point, colors color = BLUE,
718  const std::string& ns = "Wireframe Cuboid", std::size_t id = 0);
719 
729  bool publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, colors color = BLUE,
730  scales scale = MEDIUM, std::size_t id = 0);
731  bool publishWireframeRectangle(const Eigen::Isometry3d& pose, const Eigen::Vector3d& p1_in,
732  const Eigen::Vector3d& p2_in, const Eigen::Vector3d& p3_in,
733  const Eigen::Vector3d& p4_in, colors color, scales scale);
742  bool publishAxisLabeled(const Eigen::Isometry3d& pose, const std::string& label, scales scale = MEDIUM,
743  colors color = WHITE);
744  bool publishAxisLabeled(const geometry_msgs::Pose& pose, const std::string& label, scales scale = MEDIUM,
745  colors color = WHITE);
746 
756  bool publishAxis(const geometry_msgs::Pose& pose, scales scale = MEDIUM, const std::string& ns = "Axis");
757  bool publishAxis(const Eigen::Isometry3d& pose, scales scale = MEDIUM, const std::string& ns = "Axis");
758  bool publishAxis(const geometry_msgs::Pose& pose, double length, double radius = 0.01,
759  const std::string& ns = "Axis");
760  bool publishAxis(const Eigen::Isometry3d& pose, double length, double radius = 0.01, const std::string& ns = "Axis");
761 
762 private:
771  bool publishAxisInternal(const Eigen::Isometry3d& pose, double length = 0.1, double radius = 0.01,
772  const std::string& ns = "Axis");
773 
774 public:
783  bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, scales scale = MEDIUM,
784  const std::string& ns = "Axis Path");
785  bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, double length = 0.1, double radius = 0.01,
786  const std::string& ns = "Axis Path");
787 
796  bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color = BLUE,
797  scales scale = MEDIUM, const std::string& ns = "Cylinder");
798  bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color, double radius = 0.01,
799  const std::string& ns = "Cylinder");
800  bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::ColorRGBA& color,
801  double radius = 0.01, const std::string& ns = "Cylinder");
802 
811  bool publishCylinder(const Eigen::Isometry3d& pose, colors color = BLUE, double height = 0.1, double radius = 0.01,
812  const std::string& ns = "Cylinder");
813  bool publishCylinder(const geometry_msgs::Pose& pose, colors color = BLUE, double height = 0.1, double radius = 0.01,
814  const std::string& ns = "Cylinder");
815  bool publishCylinder(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color, double height = 0.1,
816  double radius = 0.01, const std::string& ns = "Cylinder");
817 
829  bool publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color = CLEAR, double scale = 1,
830  const std::string& ns = "mesh", std::size_t id = 0);
831  bool publishMesh(const geometry_msgs::Pose& pose, const std::string& file_name, colors color = CLEAR,
832  double scale = 1, const std::string& ns = "mesh", std::size_t id = 0);
833 
841  bool publishGraph(const graph_msgs::GeometryGraph& graph, colors color, double radius);
842 
852  bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color = WHITE, scales scale = MEDIUM,
853  bool static_id = true);
854  bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color,
855  const geometry_msgs::Vector3 scale, bool static_id = true);
856  bool publishText(const geometry_msgs::Pose& pose, const std::string& text, colors color = WHITE,
857  scales scale = MEDIUM, bool static_id = true);
858  bool publishText(const geometry_msgs::Pose& pose, const std::string& text, colors color,
859  const geometry_msgs::Vector3 scale, bool static_id = true);
860 
866  static geometry_msgs::Pose convertPose(const Eigen::Isometry3d& pose);
867 
873  static void convertPoseSafe(const Eigen::Isometry3d& pose, geometry_msgs::Pose& pose_msg);
874 
881  static Eigen::Isometry3d convertPose(const geometry_msgs::Pose& pose);
882 
888  static void convertPoseSafe(const geometry_msgs::Pose& pose_msg, Eigen::Isometry3d& pose);
889 
896  static Eigen::Isometry3d convertPoint32ToPose(const geometry_msgs::Point32& point);
897 
901  static geometry_msgs::Pose convertPointToPose(const geometry_msgs::Point& point);
902  static Eigen::Isometry3d convertPointToPose(const Eigen::Vector3d& point);
903 
910  static geometry_msgs::Point convertPoseToPoint(const Eigen::Isometry3d& pose);
911 
918  static Eigen::Vector3d convertPoint(const geometry_msgs::Point& point);
919 
926  static Eigen::Vector3d convertPoint32(const geometry_msgs::Point32& point);
927 
934  static geometry_msgs::Point32 convertPoint32(const Eigen::Vector3d& point);
935 
942  static geometry_msgs::Point convertPoint(const geometry_msgs::Vector3& point);
943 
950  static geometry_msgs::Point convertPoint(const Eigen::Vector3d& point);
951 
962  static Eigen::Isometry3d convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz,
963  EulerConvention convention); // ZYX is ROS standard
964  static Eigen::Isometry3d convertFromXYZRPY(const std::vector<double>& transform6,
965  EulerConvention convention); // ZYX is ROS standard
966 
967  // TODO(davetcoleman): add opposite conversion that uses Eigen::Vector3d rpy = pose.rotation().eulerAngles(0, 1, 2);
968 
975  static void convertToXYZRPY(const Eigen::Isometry3d& pose, std::vector<double>& xyzrpy);
976  static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, double& pitch,
977  double& yaw);
983  static void generateRandomPose(geometry_msgs::Pose& pose, RandomPoseBounds pose_bounds = RandomPoseBounds());
984  static void generateRandomPose(Eigen::Isometry3d& pose, RandomPoseBounds pose_bounds = RandomPoseBounds());
985 
989  static void generateRandomCuboid(geometry_msgs::Pose& cuboid_pose, double& depth, double& width, double& height,
990  RandomPoseBounds pose_bounds = RandomPoseBounds(),
991  RandomCuboidBounds cuboid_bounds = RandomCuboidBounds());
992 
997  [[deprecated("Replaced with getIdentityPose() in future releases")]] static void generateEmptyPose(geometry_msgs::Pose& pose);
998  static geometry_msgs::Pose getIdentityPose();
999 
1007  static bool posesEqual(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double threshold = 0.000001);
1008 
1012  static double dRand(double min, double max);
1013  static float fRand(float min, float max);
1014  static int iRand(int min, int max);
1015 
1019  static void printTranslation(const Eigen::Vector3d& translation);
1020 
1024  static void printTransform(const Eigen::Isometry3d& transform);
1025 
1029  static void printTransformRPY(const Eigen::Isometry3d& transform);
1030 
1034  static void printTransformFull(const Eigen::Isometry3d& transform);
1035 
1037  bool getPsychedelicMode() const
1038  {
1039  return psychedelic_mode_;
1040  }
1041 
1043  void setPsychedelicMode(bool psychedelic_mode = true)
1044  {
1045  psychedelic_mode_ = psychedelic_mode;
1046  }
1047 
1049  void prompt(const std::string& msg);
1050 
1052  RemoteControlPtr& getRemoteControl();
1053 
1055  void loadRemoteControl();
1056 
1057 protected:
1058  // A shared node handle
1060 
1061  // Short name for this class
1062  static RVIZ_VISUAL_TOOLS_DECL const std::string name_;
1063 
1064  // Optional remote control
1066 
1067  // ROS publishers
1068  ros::Publisher pub_rviz_markers_; // for rviz visualization markers
1069  bool pub_rviz_markers_connected_ = false;
1070  bool pub_rviz_markers_waited_ = false;
1071 
1072  // Strings
1073  std::string marker_topic_; // topic to publish to rviz
1074  std::string base_frame_; // name of base link
1075 
1076  // Duration to have Rviz markers persist, 0 for infinity
1078 
1079  // Settings
1080  bool batch_publishing_enabled_ = true;
1081  bool frame_locking_enabled_ = false;
1082  double alpha_ = 1.0; // opacity of all markers
1083  double global_scale_ = 1.0; // allow all markers to be increased by a constanct factor
1084 
1085  // Cached Rviz Marker Array
1086  visualization_msgs::MarkerArray markers_;
1087 
1088  // Cached Rviz markers
1089  visualization_msgs::Marker arrow_marker_;
1090  visualization_msgs::Marker sphere_marker_;
1091  visualization_msgs::Marker block_marker_;
1092  visualization_msgs::Marker cylinder_marker_;
1093  visualization_msgs::Marker mesh_marker_;
1094  visualization_msgs::Marker text_marker_;
1095  visualization_msgs::Marker cuboid_marker_;
1096  visualization_msgs::Marker line_strip_marker_;
1097  visualization_msgs::Marker line_list_marker_;
1098  visualization_msgs::Marker spheres_marker_;
1099  visualization_msgs::Marker reset_marker_;
1100  visualization_msgs::Marker triangle_marker_;
1101 
1102  // Just for fun.
1103  bool psychedelic_mode_ = false;
1104 
1105  // Chose random colors from this list
1106  static const std::array<colors, 14> all_rand_colors_;
1107 
1108 public:
1109  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // http://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
1110 }; // class
1111 
1112 typedef std::shared_ptr<RvizVisualTools> RvizVisualToolsPtr;
1113 typedef std::shared_ptr<const RvizVisualTools> RvizVisualToolsConstPtr;
1114 
1115 } // namespace rviz_visual_tools
1116 
1117 #endif // RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
visualization_msgs::Marker block_marker_
visualization_msgs::Marker sphere_marker_
ROSCPP_DECL void start()
RandomCuboidBounds(double cuboid_size_min=0.02, double cuboid_size_max=0.15)
void setBaseFrame(const std::string &base_frame)
Change the global base frame Note: this might reset all your current markers.
visualization_msgs::MarkerArray markers_
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
ROSCONSOLE_DECL void initialize()
visualization_msgs::Marker arrow_marker_
visualization_msgs::Marker text_marker_
std::shared_ptr< RemoteControl > RemoteControlPtr
void setMarkerTopic(const std::string &topic)
Set marker array topic.
static const std::array< colors, 14 > all_rand_colors_
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
std::shared_ptr< const RvizVisualTools > RvizVisualToolsConstPtr
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::shared_ptr< RvizVisualTools > RvizVisualToolsPtr
#define RVIZ_VISUAL_TOOLS_DECL
static const double SMALL_SCALE
void setGlobalScale(double global_scale)
Setter for the global scale used for changing size of all markers.
visualization_msgs::Marker cylinder_marker_
visualization_msgs::Marker line_list_marker_
Bounds for generateRandomPose()
visualization_msgs::Marker line_strip_marker_
double min(double a, double b)
void setPsychedelicMode(bool psychedelic_mode=true)
Setter for PsychedelicMode.
visualization_msgs::Marker mesh_marker_
static const double LARGE_SCALE
Bounds for generateRandomCuboid()
visualization_msgs::Marker spheres_marker_
void publishMesh(int &id, float x, float y, float r, float g, float b, float a, bool use_embedded_materials, int mesh)
void publishText(int &id, float x, float y, const std::string &text)
static const std::string RVIZ_MARKER_TOPIC
static RVIZ_VISUAL_TOOLS_DECL const std::string name_
const std::string getBaseFrame() const
Get the base frame.
bool getPsychedelicMode() const
Getter for PsychedelicMode.
visualization_msgs::Marker reset_marker_
visualization_msgs::Marker triangle_marker_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
visualization_msgs::Marker cuboid_marker_
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, double z_max=1.0, double elevation_min=0.0, double elevation_max=M_PI, double azimuth_min=0.0, double azimuth_max=2 *M_PI, double angle_min=0.0, double angle_max=2 *M_PI)
double max(double a, double b)
void setAlpha(double alpha)
Change the transparency of all markers published.
double getGlobalScale() const
Getter for the global scale used for changing size of all markers.


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