40 #include <boost/utility.hpp> 47 template <
typename GraphType>
53 typedef typename boost::graph_traits<GraphType>::vertex_iterator GraphVertexIterator;
54 typedef typename boost::graph_traits<GraphType>::edge_iterator GraphEdgeIterator;
57 visualization_msgs::Marker marker;
60 marker.ns = ns_prefix +
"Edges";
64 marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
66 marker.type = visualization_msgs::Marker::LINE_LIST;
68 marker.action = visualization_msgs::Marker::ADD;
70 GraphEdgeIterator it_edge, end_edges;
71 for (boost::tie(it_edge,end_edges) = boost::edges(graph); it_edge!=end_edges; ++it_edge)
74 geometry_msgs::Point point_start1;
75 point_start1.x = graph[boost::source(*it_edge,graph)].pos[0]+0.05;
76 point_start1.y = graph[boost::source(*it_edge,graph)].pos[1]-0.05;
78 marker.points.push_back(point_start1);
79 geometry_msgs::Point point_start2;
80 point_start2.x = graph[boost::source(*it_edge,graph)].pos[0]-0.05;
81 point_start2.y = graph[boost::source(*it_edge,graph)].pos[1]+0.05;
83 marker.points.push_back(point_start2);
86 geometry_msgs::Point point_start;
87 point_start.x = graph[boost::source(*it_edge,graph)].pos[0];
88 point_start.y = graph[boost::source(*it_edge,graph)].pos[1];
90 marker.points.push_back(point_start);
92 geometry_msgs::Point point_end;
93 point_end.x = graph[boost::target(*it_edge,graph)].pos[0];
94 point_end.y = graph[boost::target(*it_edge,graph)].pos[1];
96 marker.points.push_back(point_end);
99 std_msgs::ColorRGBA color;
104 marker.colors.push_back(color);
105 marker.colors.push_back(color);
107 marker.colors.push_back(color);
116 marker.scale.x = 0.01;
118 marker.color.a = 1.0;
119 marker.color.r = 0.0;
120 marker.color.g = 1.0;
121 marker.color.b = 0.0;
129 marker.ns = ns_prefix +
"Vertices";
131 marker.type = visualization_msgs::Marker::POINTS;
132 marker.action = visualization_msgs::Marker::ADD;
134 GraphVertexIterator it_vert, end_vert;
135 for (boost::tie(it_vert,end_vert) =
boost::vertices(graph); it_vert!=end_vert; ++it_vert)
137 geometry_msgs::Point
point;
138 point.x = graph[*it_vert].pos[0];
139 point.y = graph[*it_vert].pos[1];
141 marker.points.push_back(point);
144 std_msgs::ColorRGBA color;
146 if (it_vert==end_vert-1)
158 marker.colors.push_back(color);
161 if (!marker.colors.empty())
163 marker.colors.front().b = 1;
164 marker.colors.front().g = 0;
167 marker.scale.x = 0.1;
168 marker.scale.y = 0.1;
169 marker.color.a = 1.0;
170 marker.color.r = 0.0;
171 marker.color.g = 1.0;
172 marker.color.b = 0.0;
178 template <
typename B
idirIter>
184 visualization_msgs::Marker marker;
189 marker.type = visualization_msgs::Marker::LINE_LIST;
190 marker.action = visualization_msgs::Marker::ADD;
192 typedef typename std::iterator_traits<BidirIter>::value_type PathType;
198 typename PathType::const_iterator it_point, end_point;
199 for (it_point = first->begin(), end_point = boost::prior(first->end()); it_point != end_point; ++it_point)
201 geometry_msgs::Point point_start;
205 marker.points.push_back(point_start);
207 geometry_msgs::Point point_end;
211 marker.points.push_back(point_end);
215 marker.scale.x = 0.01;
216 marker.color.a = 1.0;
217 marker.color.r = 0.0;
218 marker.color.g = 1.0;
219 marker.color.b = 0.0;
std::string map_frame
Global planning frame.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
void publish(const boost::shared_ptr< M > &message) const
void publishPathContainer(BidirIter first, BidirIter last, const std::string &ns="PathContainer")
Publish multiple 2D paths (each path given as a point sequence) from a container class.
const T & get_const_reference(const T *ptr)
Helper function that returns the const reference to a value defined by either its raw pointer type or...
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not...
void publishGraph(const GraphType &graph, const std::string &ns_prefix="Graph")
Publish a boost::adjacency_list (boost's graph datatype) via markers.
ros::Publisher teb_marker_pub_
Publisher for visualization markers.