@@ -54,9 +54,6 @@ namespace rviz_visual_tools
5454
5555const std::string LOGNAME = " visual_tools" ;
5656
57- // DEPRECATED, remove in Melodic after Dec 2018 release or so
58- const std::string RvizVisualTools::name_ = " visual_tools" ;
59-
6057const std::array<colors, 14 > RvizVisualTools::all_rand_colors_ = { RED, GREEN, BLUE, GREY, DARK_GREY,
6158 WHITE, ORANGE, YELLOW, BROWN, PINK,
6259 LIME_GREEN, PURPLE, CYAN, MAGENTA };
@@ -102,7 +99,7 @@ bool RvizVisualTools::loadRvizMarkers()
10299 reset_marker_.header .frame_id = base_frame_;
103100 reset_marker_.header .stamp = ros::Time ();
104101 reset_marker_.ns = " deleteAllMarkers" ; // helps during debugging
105- reset_marker_.action = 3 ; // TODO(davetcoleman): In ROS-J set to visualization_msgs::Marker::DELETEALL;
102+ reset_marker_.action = visualization_msgs::Marker::DELETEALL;
106103 reset_marker_.pose .orientation .w = 1 ;
107104
108105 // Load arrow ----------------------------------------------------
@@ -871,13 +868,13 @@ bool RvizVisualTools::trigger()
871868 return false ;
872869 }
873870
874- bool result = publishMarkers (markers_);
871+ bool result = publishMarkersWithoutTrigger (markers_);
875872
876873 markers_.markers .clear (); // remove all cached markers
877874 return result;
878875}
879876
880- bool RvizVisualTools::publishMarkers (visualization_msgs::MarkerArray& markers)
877+ bool RvizVisualTools::publishMarkersWithoutTrigger (visualization_msgs::MarkerArray& markers)
881878{
882879 if (pub_rviz_markers_ == nullptr )
883880 { // always check this before publishing
@@ -1629,13 +1626,13 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const std::st
16291626 return publishMarker (mesh_marker_);
16301627}
16311628
1632- bool RvizVisualTools::publishMesh (const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color,
1629+ bool RvizVisualTools::publishMesh (const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color,
16331630 double scale, const std::string& ns, std::size_t id)
16341631{
16351632 return publishMesh (convertPose (pose), mesh, color, scale, ns, id);
16361633}
16371634
1638- bool RvizVisualTools::publishMesh (const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color,
1635+ bool RvizVisualTools::publishMesh (const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color,
16391636 double scale, const std::string& ns, std::size_t id)
16401637{
16411638 triangle_marker_.header .stamp = ros::Time::now ();
0 commit comments