42 #include <nav_msgs/OccupancyGrid.h>
43 #include <geometry_msgs/PolygonStamped.h>
44 #include <visualization_msgs/Marker.h>
57 std::string converter_plugin =
"costmap_converter::CostmapToPolygonsDBSMCCH";
58 n_.
param(
"converter_plugin", converter_plugin, converter_plugin);
66 ROS_ERROR(
"The plugin failed to load for some reason. Error: %s", ex.what());
70 ROS_INFO_STREAM(
"Standalone costmap converter:" << converter_plugin <<
" loaded.");
72 std::string costmap_topic =
"/move_base/local_costmap/costmap";
73 n_.
param(
"costmap_topic", costmap_topic, costmap_topic);
75 std::string costmap_update_topic =
"/move_base/local_costmap/costmap_updates";
76 n_.
param(
"costmap_update_topic", costmap_update_topic, costmap_update_topic);
78 std::string obstacles_topic =
"costmap_obstacles";
79 n_.
param(
"obstacles_topic", obstacles_topic, obstacles_topic);
81 std::string polygon_marker_topic =
"costmap_polygon_markers";
82 n_.
param(
"polygon_marker_topic", polygon_marker_topic, polygon_marker_topic);
92 std::string odom_topic =
"/odom";
93 n_.
param(
"odom_topic", odom_topic, odom_topic);
107 ROS_INFO_ONCE(
"Got first costmap callback. This message will be printed once");
111 ROS_INFO(
"New map format, resizing and resetting map...");
112 map_.
resizeMap(msg->info.width, msg->info.height, msg->info.resolution, msg->info.origin.position.x, msg->info.origin.position.y);
116 map_.
updateOrigin(msg->info.origin.position.x, msg->info.origin.position.y);
120 for (std::size_t i=0; i < msg->data.size(); ++i)
143 for (
unsigned int y = 0; y <
update->height ; ++y)
145 for (
unsigned int x = 0; x <
update->width ; ++x)
165 void publishAsMarker(
const std::string& frame_id,
const std::vector<geometry_msgs::PolygonStamped>& polygonStamped,
ros::Publisher& marker_pub)
167 visualization_msgs::Marker line_list;
168 line_list.header.frame_id = frame_id;
170 line_list.ns =
"Polygons";
171 line_list.action = visualization_msgs::Marker::ADD;
172 line_list.pose.orientation.w = 1.0;
175 line_list.type = visualization_msgs::Marker::LINE_LIST;
177 line_list.scale.x = 0.1;
178 line_list.color.g = 1.0;
179 line_list.color.a = 1.0;
181 for (std::size_t i=0; i<polygonStamped.size(); ++i)
183 for (
int j=0; j< (int)polygonStamped[i].polygon.points.size()-1; ++j)
185 geometry_msgs::Point line_start;
186 line_start.x = polygonStamped[i].polygon.points[j].x;
187 line_start.y = polygonStamped[i].polygon.points[j].y;
188 line_list.points.push_back(line_start);
189 geometry_msgs::Point line_end;
190 line_end.x = polygonStamped[i].polygon.points[j+1].x;
191 line_end.y = polygonStamped[i].polygon.points[j+1].y;
192 line_list.points.push_back(line_end);
195 if (!polygonStamped[i].polygon.points.empty() && polygonStamped[i].polygon.points.size() != 2 )
197 geometry_msgs::Point line_start;
198 line_start.x = polygonStamped[i].polygon.points.back().x;
199 line_start.y = polygonStamped[i].polygon.points.back().y;
200 line_list.points.push_back(line_start);
201 if (line_list.points.size() % 2 != 0)
203 geometry_msgs::Point line_end;
204 line_end.x = polygonStamped[i].polygon.points.front().x;
205 line_end.y = polygonStamped[i].polygon.points.front().y;
206 line_list.points.push_back(line_end);
217 visualization_msgs::Marker line_list;
218 line_list.header.frame_id = frame_id;
220 line_list.ns =
"Polygons";
221 line_list.action = visualization_msgs::Marker::ADD;
222 line_list.pose.orientation.w = 1.0;
225 line_list.type = visualization_msgs::Marker::LINE_LIST;
227 line_list.scale.x = 0.1;
228 line_list.color.g = 1.0;
229 line_list.color.a = 1.0;
231 for (
const costmap_converter::ObstacleMsg& obstacle : obstacles.obstacles)
233 for (
int j=0; j< (int)obstacle.polygon.points.size()-1; ++j)
235 geometry_msgs::Point line_start;
236 line_start.x = obstacle.polygon.points[j].x;
237 line_start.y = obstacle.polygon.points[j].y;
238 line_list.points.push_back(line_start);
239 geometry_msgs::Point line_end;
240 line_end.x = obstacle.polygon.points[j+1].x;
241 line_end.y = obstacle.polygon.points[j+1].y;
242 line_list.points.push_back(line_end);
245 if (!obstacle.polygon.points.empty() && obstacle.polygon.points.size() != 2 )
247 geometry_msgs::Point line_start;
248 line_start.x = obstacle.polygon.points.back().x;
249 line_start.y = obstacle.polygon.points.back().y;
250 line_list.points.push_back(line_start);
251 if (line_list.points.size() % 2 != 0)
253 geometry_msgs::Point line_end;
254 line_end.x = obstacle.polygon.points.front().x;
255 line_end.y = obstacle.polygon.points.front().y;
256 line_list.points.push_back(line_end);
282 int main(
int argc,
char** argv)
284 ros::init(argc, argv,
"costmap_converter");