39 #ifndef RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H 40 #define RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H 49 #include <Eigen/Geometry> 53 #include <visualization_msgs/Marker.h> 54 #include <visualization_msgs/MarkerArray.h> 57 #include <boost/shared_ptr.hpp> 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> 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 79 #else // ros is being built around static libraries 80 #define RVIZ_VISUAL_TOOLS_DECL 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)
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;
179 cuboid_size_min_ = cuboid_size_min;
180 cuboid_size_max_ = cuboid_size_max;
210 bool deleteAllMarkers();
216 void resetMarkerCounts();
222 bool loadRvizMarkers();
227 marker_topic_ = topic;
235 void loadMarkerPub(
bool wait_for_subscriber =
false,
bool latched =
false);
240 void waitForMarkerPub();
241 void waitForMarkerPub(
double wait_time);
250 bool waitForSubscriber(
const ros::Publisher& pub,
double wait_time = 0.5,
bool blocking =
false);
264 void setLifetime(
double lifetime);
270 static colors getRandColor();
277 std_msgs::ColorRGBA getColor(
colors color)
const;
280 static colors intToRvizColor(std::size_t color);
286 static std::string scaleToString(
scales scale);
292 std_msgs::ColorRGBA createRandColor()
const;
298 static double slerp(
double start,
double end,
double range,
double value);
304 std_msgs::ColorRGBA getColorScale(
double value)
const;
312 geometry_msgs::Vector3 getScale(
scales scale,
double marker_scale = 1.0)
const;
320 Eigen::Isometry3d getVectorBetweenPoints(
const Eigen::Vector3d& a,
const Eigen::Vector3d& b)
const;
328 Eigen::Vector3d getCenterPoint(
const Eigen::Vector3d& a,
const Eigen::Vector3d& b)
const;
345 base_frame_ = base_frame;
354 return global_scale_;
361 global_scale_ = global_scale;
368 bool publishMarker(visualization_msgs::Marker& marker);
375 void enableBatchPublishing(
bool enable =
true);
381 void enableFrameLocking(
bool enable =
true);
390 bool triggerEvery(std::size_t queueSize);
403 bool publishMarkers(visualization_msgs::MarkerArray& markers);
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);
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);
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);
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);
456 const std::string& ns =
"Sphere", std::size_t
id = 0);
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",
462 const std::string& ns =
"Sphere", std::size_t
id = 0);
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",
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);
487 const std::string& ns =
"Spheres");
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");
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");
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,
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,
544 bool publishZArrow(
const Eigen::Isometry3d& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.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,
549 bool publishZArrow(
const geometry_msgs::PoseStamped& pose, colors color =
BLUE,
scales scale =
MEDIUM,
550 double length = 0.0, std::size_t
id = 0);
562 bool publishArrow(
const Eigen::Isometry3d& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.0,
564 bool publishArrow(
const geometry_msgs::Pose& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.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,
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);
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);
602 bool publishLine(
const Eigen::Isometry3d& point1,
const Eigen::Isometry3d& point2, colors color =
BLUE,
604 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color =
BLUE,
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,
609 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2,
const std_msgs::ColorRGBA& color,
611 bool publishLine(
const geometry_msgs::Point& point1,
const geometry_msgs::Point& point2, colors color =
BLUE,
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);
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);
639 bool publishLineStrip(
const std::vector<geometry_msgs::Point>& path, colors color =
RED,
scales scale =
MEDIUM,
640 const std::string& ns =
"Path");
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");
655 const std::string& ns =
"Path");
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");
661 const std::string& ns =
"Path");
663 const std::string& ns =
"Path");
675 const std::string& ns =
"Path");
678 const std::string& ns =
"Path");
688 bool publishPolygon(
const geometry_msgs::Polygon& polygon, colors color =
RED,
scales scale =
MEDIUM,
689 const std::string& ns =
"Polygon");
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);
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);
729 bool publishWireframeRectangle(
const Eigen::Isometry3d& pose,
double height,
double width, colors color =
BLUE,
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);
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");
771 bool publishAxisInternal(
const Eigen::Isometry3d& pose,
double length = 0.1,
double radius = 0.01,
772 const std::string& ns =
"Axis");
784 const std::string& ns =
"Axis Path");
786 const std::string& ns =
"Axis Path");
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");
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");
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);
841 bool publishGraph(
const graph_msgs::GeometryGraph& graph, colors color,
double radius);
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,
858 bool publishText(
const geometry_msgs::Pose& pose,
const std::string& text, colors color,
859 const geometry_msgs::Vector3 scale,
bool static_id =
true);
866 static geometry_msgs::Pose convertPose(
const Eigen::Isometry3d& pose);
873 static void convertPoseSafe(
const Eigen::Isometry3d& pose, geometry_msgs::Pose& pose_msg);
881 static Eigen::Isometry3d convertPose(
const geometry_msgs::Pose& pose);
888 static void convertPoseSafe(
const geometry_msgs::Pose& pose_msg, Eigen::Isometry3d& pose);
896 static Eigen::Isometry3d convertPoint32ToPose(
const geometry_msgs::Point32& point);
901 static geometry_msgs::Pose convertPointToPose(
const geometry_msgs::Point& point);
902 static Eigen::Isometry3d convertPointToPose(
const Eigen::Vector3d& point);
910 static geometry_msgs::Point convertPoseToPoint(
const Eigen::Isometry3d& pose);
918 static Eigen::Vector3d convertPoint(
const geometry_msgs::Point& point);
926 static Eigen::Vector3d convertPoint32(
const geometry_msgs::Point32& point);
934 static geometry_msgs::Point32 convertPoint32(
const Eigen::Vector3d& point);
942 static geometry_msgs::Point convertPoint(
const geometry_msgs::Vector3& point);
950 static geometry_msgs::Point convertPoint(
const Eigen::Vector3d& point);
962 static Eigen::Isometry3d convertFromXYZRPY(
double tx,
double ty,
double tz,
double rx,
double ry,
double rz,
964 static Eigen::Isometry3d convertFromXYZRPY(
const std::vector<double>& transform6,
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,
989 static void generateRandomCuboid(geometry_msgs::Pose& cuboid_pose,
double& depth,
double& width,
double& height,
997 [[deprecated(
"Replaced with getIdentityPose() in future releases")]]
static void generateEmptyPose(geometry_msgs::Pose& pose);
998 static geometry_msgs::Pose getIdentityPose();
1007 static bool posesEqual(
const Eigen::Isometry3d& pose1,
const Eigen::Isometry3d& pose2,
double threshold = 0.000001);
1012 static double dRand(
double min,
double max);
1013 static float fRand(
float min,
float max);
1014 static int iRand(
int min,
int max);
1019 static void printTranslation(
const Eigen::Vector3d& translation);
1024 static void printTransform(
const Eigen::Isometry3d& transform);
1029 static void printTransformRPY(
const Eigen::Isometry3d& transform);
1034 static void printTransformFull(
const Eigen::Isometry3d& transform);
1039 return psychedelic_mode_;
1045 psychedelic_mode_ = psychedelic_mode;
1049 void prompt(
const std::string& msg);
1055 void loadRemoteControl();
1069 bool pub_rviz_markers_connected_ =
false;
1070 bool pub_rviz_markers_waited_ =
false;
1080 bool batch_publishing_enabled_ =
true;
1081 bool frame_locking_enabled_ =
false;
1082 double alpha_ = 1.0;
1083 double global_scale_ = 1.0;
1103 bool psychedelic_mode_ =
false;
1109 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1117 #endif // RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
ROSCONSOLE_DECL void initialize()
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double min(double a, double b)
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)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
double max(double a, double b)