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> 139 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,
140 double z_max = 1.0,
double elevation_min = 0.0,
double elevation_max = M_PI,
141 double azimuth_min = 0.0,
double azimuth_max = 2 * M_PI,
double angle_min = 0.0,
142 double angle_max = 2 * M_PI)
150 elevation_min_ = elevation_min;
151 elevation_max_ = elevation_max;
152 azimuth_min_ = azimuth_min;
153 azimuth_max_ = azimuth_max;
154 angle_min_ = angle_min;
155 angle_max_ = angle_max;
168 cuboid_size_min_ = cuboid_size_min;
169 cuboid_size_max_ = cuboid_size_max;
199 bool deleteAllMarkers();
205 void resetMarkerCounts();
211 bool loadRvizMarkers();
216 marker_topic_ = topic;
224 void loadMarkerPub(
bool wait_for_subscriber =
false,
bool latched =
false);
229 void waitForMarkerPub();
230 void waitForMarkerPub(
double wait_time);
239 bool waitForSubscriber(
const ros::Publisher& pub,
double wait_time = 0.5,
bool blocking =
false);
253 void setLifetime(
double lifetime);
259 static colors getRandColor();
266 std_msgs::ColorRGBA getColor(
colors color)
const;
269 static colors intToRvizColor(std::size_t color);
275 static std::string scaleToString(
scales scale);
281 std_msgs::ColorRGBA createRandColor()
const;
287 static double slerp(
double start,
double end,
double range,
double value);
293 std_msgs::ColorRGBA getColorScale(
double value)
const;
301 geometry_msgs::Vector3 getScale(
scales scale,
double marker_scale = 1.0)
const;
309 Eigen::Affine3d getVectorBetweenPoints(
const Eigen::Vector3d& a,
const Eigen::Vector3d& b)
const;
317 Eigen::Vector3d getCenterPoint(
const Eigen::Vector3d& a,
const Eigen::Vector3d& b)
const;
334 base_frame_ = base_frame;
343 return global_scale_;
350 global_scale_ = global_scale;
357 bool publishMarker(visualization_msgs::Marker& marker);
364 void enableBatchPublishing(
bool enable =
true);
370 void enableFrameLocking(
bool enable =
true);
379 bool triggerEvery(std::size_t queueSize);
400 bool triggerAndDisable();
407 bool publishMarkers(visualization_msgs::MarkerArray& markers);
416 bool publishCone(
const Eigen::Affine3d& pose,
double angle,
colors color =
TRANSLUCENT,
double scale = 1.0);
417 bool publishCone(
const geometry_msgs::Pose& pose,
double angle,
colors color =
TRANSLUCENT,
double scale = 1.0);
426 bool publishXYPlane(
const Eigen::Affine3d& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
427 bool publishXYPlane(
const geometry_msgs::Pose& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
436 bool publishXZPlane(
const Eigen::Affine3d& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
437 bool publishXZPlane(
const geometry_msgs::Pose& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
446 bool publishYZPlane(
const Eigen::Affine3d& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
447 bool publishYZPlane(
const geometry_msgs::Pose& pose,
colors color =
TRANSLUCENT,
double scale = 1.0);
460 const std::string& ns =
"Sphere", std::size_t
id = 0);
462 const std::string& ns =
"Sphere", std::size_t
id = 0);
463 bool publishSphere(
const Eigen::Vector3d& point,
colors color,
double scale,
const std::string& ns =
"Sphere",
466 const std::string& ns =
"Sphere", std::size_t
id = 0);
468 const std::string& ns =
"Sphere", std::size_t
id = 0);
469 bool publishSphere(
const geometry_msgs::Pose& pose,
colors color,
double scale,
const std::string& ns =
"Sphere",
471 bool publishSphere(
const geometry_msgs::Pose& pose,
colors color,
const geometry_msgs::Vector3 scale,
472 const std::string& ns =
"Sphere", std::size_t
id = 0);
473 bool publishSphere(
const geometry_msgs::Pose& pose,
const std_msgs::ColorRGBA& color,
474 const geometry_msgs::Vector3 scale,
const std::string& ns =
"Sphere", std::size_t
id = 0);
475 bool publishSphere(
const Eigen::Affine3d& pose,
const std_msgs::ColorRGBA& color,
const geometry_msgs::Vector3 scale,
476 const std::string& ns =
"Sphere", std::size_t
id = 0);
477 bool publishSphere(
const Eigen::Vector3d& point,
const std_msgs::ColorRGBA& color,
const geometry_msgs::Vector3 scale,
478 const std::string& ns =
"Sphere", std::size_t
id = 0);
479 bool publishSphere(
const geometry_msgs::PoseStamped& pose,
colors color,
const geometry_msgs::Vector3 scale,
480 const std::string& ns =
"Sphere", std::size_t
id = 0);
491 const std::string& ns =
"Spheres");
493 const std::string& ns =
"Spheres");
494 bool publishSpheres(
const std::vector<geometry_msgs::Point>& points,
colors color =
BLUE,
scales scale =
MEDIUM,
495 const std::string& ns =
"Spheres");
496 bool publishSpheres(
const std::vector<geometry_msgs::Point>& points,
colors color =
BLUE,
double scale = 0.1,
497 const std::string& ns =
"Spheres");
498 bool publishSpheres(
const std::vector<geometry_msgs::Point>& points,
colors color,
499 const geometry_msgs::Vector3& scale,
const std::string& ns =
"Spheres");
510 const std::string& ns =
"Spheres");
511 bool publishSpheres(
const std::vector<geometry_msgs::Point>& points,
const std::vector<std_msgs::ColorRGBA>& colors,
512 const geometry_msgs::Vector3& scale,
const std::string& ns =
"Spheres");
522 bool publishXArrow(
const Eigen::Affine3d& pose, colors color =
RED,
scales scale =
MEDIUM,
double length = 0.0);
523 bool publishXArrow(
const geometry_msgs::Pose& pose, colors color =
RED,
scales scale =
MEDIUM,
double length = 0.0);
524 bool publishXArrow(
const geometry_msgs::PoseStamped& pose, colors color =
RED,
scales scale =
MEDIUM,
525 double length = 0.0);
535 bool publishYArrow(
const Eigen::Affine3d& pose, colors color =
GREEN,
scales scale =
MEDIUM,
double length = 0.0);
536 bool publishYArrow(
const geometry_msgs::Pose& pose, colors color =
GREEN,
scales scale =
MEDIUM,
double length = 0.0);
537 bool publishYArrow(
const geometry_msgs::PoseStamped& pose, colors color =
GREEN,
scales scale =
MEDIUM,
538 double length = 0.0);
548 bool publishZArrow(
const Eigen::Affine3d& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.0,
550 bool publishZArrow(
const geometry_msgs::Pose& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.0);
551 bool publishZArrow(
const geometry_msgs::PoseStamped& pose, colors color =
BLUE,
scales scale =
MEDIUM,
552 double length = 0.0);
553 bool publishZArrow(
const geometry_msgs::PoseStamped& pose, colors color =
BLUE,
scales scale =
MEDIUM,
554 double length = 0.0, std::size_t
id = 0);
566 bool publishArrow(
const Eigen::Affine3d& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.0,
568 bool publishArrow(
const geometry_msgs::Pose& pose, colors color =
BLUE,
scales scale =
MEDIUM,
double length = 0.0,
570 bool publishArrow(
const geometry_msgs::PoseStamped& pose, colors color =
BLUE,
scales scale =
MEDIUM,
571 double length = 0.0, std::size_t
id = 0);
572 bool publishArrow(
const geometry_msgs::Point& start,
const geometry_msgs::Point& end, colors color =
BLUE,
582 bool publishCuboid(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color =
BLUE);
583 bool publishCuboid(
const geometry_msgs::Point& point1,
const geometry_msgs::Point& point2, colors color =
BLUE,
584 const std::string& ns =
"Cuboid", std::size_t
id = 0);
595 bool publishCuboid(
const geometry_msgs::Pose& pose,
double depth,
double width,
double height, colors color =
BLUE);
596 bool publishCuboid(
const Eigen::Affine3d& pose,
double depth,
double width,
double height, colors color =
BLUE);
606 bool publishLine(
const Eigen::Affine3d& point1,
const Eigen::Affine3d& point2, colors color =
BLUE,
608 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color =
BLUE,
610 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color,
double radius);
611 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2,
const std_msgs::ColorRGBA& color,
613 bool publishLine(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2,
const std_msgs::ColorRGBA& color,
615 bool publishLine(
const geometry_msgs::Point& point1,
const geometry_msgs::Point& point2, colors color =
BLUE,
617 bool publishLine(
const geometry_msgs::Point& point1,
const geometry_msgs::Point& point2,
618 const std_msgs::ColorRGBA& color,
scales scale =
MEDIUM);
619 bool publishLine(
const geometry_msgs::Point& point1,
const geometry_msgs::Point& point2,
620 const std_msgs::ColorRGBA& color,
const geometry_msgs::Vector3& scale);
631 const std::vector<colors>& colors,
scales scale =
MEDIUM);
632 bool publishLines(
const std::vector<geometry_msgs::Point>& aPoints,
const std::vector<geometry_msgs::Point>& bPoints,
633 const std::vector<std_msgs::ColorRGBA>& colors,
const geometry_msgs::Vector3& scale);
643 bool publishLineStrip(
const std::vector<geometry_msgs::Point>& path, colors color =
RED,
scales scale =
MEDIUM,
644 const std::string& ns =
"Path");
654 bool publishPath(
const std::vector<geometry_msgs::Pose>& path, colors color =
RED,
scales scale =
MEDIUM,
655 const std::string& ns =
"Path");
656 bool publishPath(
const std::vector<geometry_msgs::Point>& path, colors color =
RED,
scales scale =
MEDIUM,
657 const std::string& ns =
"Path");
659 const std::string& ns =
"Path");
661 const std::string& ns =
"Path");
662 bool publishPath(
const std::vector<geometry_msgs::Point>& path, colors color =
RED,
double radius = 0.01,
663 const std::string& ns =
"Path");
665 const std::string& ns =
"Path");
667 const std::string& ns =
"Path");
679 const std::string& ns =
"Path");
682 const std::string& ns =
"Path");
692 bool publishPolygon(
const geometry_msgs::Polygon& polygon, colors color =
RED,
scales scale =
MEDIUM,
693 const std::string& ns =
"Polygon");
707 bool publishWireframeCuboid(
const Eigen::Affine3d& pose,
double depth,
double width,
double height,
708 colors color =
BLUE,
const std::string& ns =
"Wireframe Cuboid", std::size_t
id = 0);
720 bool publishWireframeCuboid(
const Eigen::Affine3d& pose,
const Eigen::Vector3d& min_point,
721 const Eigen::Vector3d& max_point, colors color =
BLUE,
722 const std::string& ns =
"Wireframe Cuboid", std::size_t
id = 0);
733 bool publishWireframeRectangle(
const Eigen::Affine3d& pose,
double height,
double width, colors color =
BLUE,
735 bool publishWireframeRectangle(
const Eigen::Affine3d& pose,
const Eigen::Vector3d& p1_in,
736 const Eigen::Vector3d& p2_in,
const Eigen::Vector3d& p3_in,
737 const Eigen::Vector3d& p4_in, colors color,
scales scale);
746 bool publishAxisLabeled(
const Eigen::Affine3d& pose,
const std::string& label,
scales scale =
MEDIUM,
747 colors color =
WHITE);
748 bool publishAxisLabeled(
const geometry_msgs::Pose& pose,
const std::string& label,
scales scale =
MEDIUM,
749 colors color =
WHITE);
760 bool publishAxis(
const geometry_msgs::Pose& pose,
scales scale =
MEDIUM,
const std::string& ns =
"Axis");
761 bool publishAxis(
const Eigen::Affine3d& pose,
scales scale =
MEDIUM,
const std::string& ns =
"Axis");
762 bool publishAxis(
const geometry_msgs::Pose& pose,
double length,
double radius = 0.01,
763 const std::string& ns =
"Axis");
764 bool publishAxis(
const Eigen::Affine3d& pose,
double length,
double radius = 0.01,
const std::string& ns =
"Axis");
775 bool publishAxisInternal(
const Eigen::Affine3d& pose,
double length = 0.1,
double radius = 0.01,
776 const std::string& ns =
"Axis");
788 const std::string& ns =
"Axis Path");
790 const std::string& ns =
"Axis Path");
800 bool publishCylinder(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color =
BLUE,
801 scales scale =
MEDIUM,
const std::string& ns =
"Cylinder");
802 bool publishCylinder(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2, colors color,
double radius = 0.01,
803 const std::string& ns =
"Cylinder");
804 bool publishCylinder(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2,
const std_msgs::ColorRGBA& color,
805 double radius = 0.01,
const std::string& ns =
"Cylinder");
815 bool publishCylinder(
const Eigen::Affine3d& pose, colors color =
BLUE,
double height = 0.1,
double radius = 0.01,
816 const std::string& ns =
"Cylinder");
817 bool publishCylinder(
const geometry_msgs::Pose& pose, colors color =
BLUE,
double height = 0.1,
double radius = 0.01,
818 const std::string& ns =
"Cylinder");
819 bool publishCylinder(
const geometry_msgs::Pose& pose,
const std_msgs::ColorRGBA& color,
double height = 0.1,
820 double radius = 0.01,
const std::string& ns =
"Cylinder");
833 bool publishMesh(
const Eigen::Affine3d& pose,
const std::string& file_name, colors color =
CLEAR,
double scale = 1,
834 const std::string& ns =
"mesh", std::size_t
id = 0);
835 bool publishMesh(
const geometry_msgs::Pose& pose,
const std::string& file_name, colors color =
CLEAR,
836 double scale = 1,
const std::string& ns =
"mesh", std::size_t
id = 0);
845 bool publishGraph(
const graph_msgs::GeometryGraph& graph, colors color,
double radius);
857 bool static_id =
true);
858 bool publishText(
const Eigen::Affine3d& pose,
const std::string& text, colors color,
859 const geometry_msgs::Vector3 scale,
bool static_id =
true);
860 bool publishText(
const geometry_msgs::Pose& pose,
const std::string& text, colors color =
WHITE,
862 bool publishText(
const geometry_msgs::Pose& pose,
const std::string& text, colors color,
863 const geometry_msgs::Vector3 scale,
bool static_id =
true);
870 static geometry_msgs::Pose convertPose(
const Eigen::Affine3d& pose);
877 static void convertPoseSafe(
const Eigen::Affine3d& pose, geometry_msgs::Pose& pose_msg);
885 static Eigen::Affine3d convertPose(
const geometry_msgs::Pose& pose);
892 static void convertPoseSafe(
const geometry_msgs::Pose& pose_msg, Eigen::Affine3d& pose);
900 static Eigen::Affine3d convertPoint32ToPose(
const geometry_msgs::Point32& point);
905 static geometry_msgs::Pose convertPointToPose(
const geometry_msgs::Point& point);
906 static Eigen::Affine3d convertPointToPose(
const Eigen::Vector3d& point);
914 static geometry_msgs::Point convertPoseToPoint(
const Eigen::Affine3d& pose);
922 static Eigen::Vector3d convertPoint(
const geometry_msgs::Point& point);
930 static Eigen::Vector3d convertPoint32(
const geometry_msgs::Point32& point);
938 static geometry_msgs::Point32 convertPoint32(
const Eigen::Vector3d& point);
946 static geometry_msgs::Point convertPoint(
const geometry_msgs::Vector3& point);
954 static geometry_msgs::Point convertPoint(
const Eigen::Vector3d& point);
965 static Eigen::Affine3d convertFromXYZRPY(
double x,
double y,
double z,
double roll,
double pitch,
double yaw);
967 static Eigen::Affine3d convertFromXYZRPY(
const std::vector<double>& transform6);
980 static Eigen::Affine3d convertFromXYZRPY(
double tx,
double ty,
double tz,
double rx,
double ry,
double rz,
982 static Eigen::Affine3d convertFromXYZRPY(
const std::vector<double>& transform6,
993 static void convertToXYZRPY(
const Eigen::Affine3d& pose, std::vector<double>& xyzrpy);
994 static void convertToXYZRPY(
const Eigen::Affine3d& pose,
double& x,
double& y,
double& z,
double& roll,
double& pitch,
1007 static void generateRandomCuboid(geometry_msgs::Pose& cuboid_pose,
double& depth,
double& width,
double& height,
1015 static void generateEmptyPose(geometry_msgs::Pose& pose);
1024 static bool posesEqual(
const Eigen::Affine3d& pose1,
const Eigen::Affine3d& pose2,
double threshold = 0.000001);
1029 static double dRand(
double min,
double max);
1030 static float fRand(
float min,
float max);
1031 static int iRand(
int min,
int max);
1036 static void printTranslation(
const Eigen::Vector3d& translation);
1041 static void printTransform(
const Eigen::Affine3d& transform);
1046 static void printTransformRPY(
const Eigen::Affine3d& transform);
1051 static void printTransformFull(
const Eigen::Affine3d& transform);
1056 return psychedelic_mode_;
1062 psychedelic_mode_ = psychedelic_mode;
1066 void prompt(
const std::string& msg);
1072 void loadRemoteControl();
1086 bool pub_rviz_markers_connected_ =
false;
1087 bool pub_rviz_markers_waited_ =
false;
1097 bool batch_publishing_enabled_ =
true;
1098 bool frame_locking_enabled_ =
false;
1099 double alpha_ = 1.0;
1100 double global_scale_ = 1.0;
1120 bool psychedelic_mode_ =
false;
1126 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1134 #endif // RVIZ_VISUAL_TOOLS_RVIZ_VISUAL_TOOLS_H
#define RVIZ_VISUAL_TOOLS_DEPRECATED
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
ROSCONSOLE_DECL void initialize()
void publishMesh(int id, float x, float y, float r, float g, float b, float a, bool use_embedded_materials, bool mesh)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
double min(double a, double b)
TFSIMD_FORCE_INLINE const tfScalar & z() const
double max(double a, double b)
void publishText(int id, float x, float y, const std::string &text)