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);
    90       n_.
param(
"occupied_min_value", occupied_min_value_, occupied_min_value_);
    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)
   145     for (
unsigned int y = 0; 
y < update->height ; ++
y)
   147       for (
unsigned int x = 0; 
x < update->width ; ++
x)
   169     visualization_msgs::Marker line_list;
   170     line_list.header.frame_id = frame_id;
   172     line_list.ns = 
"Polygons";
   173     line_list.action = visualization_msgs::Marker::ADD;
   174     line_list.pose.orientation.w = 1.0;
   177     line_list.type = visualization_msgs::Marker::LINE_LIST;
   179     line_list.scale.x = 0.1;
   180     line_list.color.g = 1.0;
   181     line_list.color.a = 1.0;
   183     for (std::size_t i=0; i<polygonStamped.size(); ++i)
   185       for (
int j=0; j< (int)polygonStamped[i].polygon.points.size()-1; ++j)
   187         geometry_msgs::Point line_start;
   188         line_start.x = polygonStamped[i].polygon.points[j].x;
   189         line_start.y = polygonStamped[i].polygon.points[j].y;
   190         line_list.points.push_back(line_start);
   191         geometry_msgs::Point line_end;
   192         line_end.x = polygonStamped[i].polygon.points[j+1].x;
   193         line_end.y = polygonStamped[i].polygon.points[j+1].y;
   194         line_list.points.push_back(line_end);
   197       if (!polygonStamped[i].polygon.points.empty() && polygonStamped[i].polygon.points.size() != 2 )
   199         geometry_msgs::Point line_start;
   200         line_start.x = polygonStamped[i].polygon.points.back().x;
   201         line_start.y = polygonStamped[i].polygon.points.back().y;
   202         line_list.points.push_back(line_start);
   203         if (line_list.points.size() % 2 != 0)
   205           geometry_msgs::Point line_end;
   206           line_end.x = polygonStamped[i].polygon.points.front().x;
   207           line_end.y = polygonStamped[i].polygon.points.front().y;
   208           line_list.points.push_back(line_end);
   219     visualization_msgs::Marker line_list;
   220     line_list.header.frame_id = frame_id;
   222     line_list.ns = 
"Polygons";
   223     line_list.action = visualization_msgs::Marker::ADD;
   224     line_list.pose.orientation.w = 1.0;
   227     line_list.type = visualization_msgs::Marker::LINE_LIST;
   229     line_list.scale.x = 0.1;
   230     line_list.color.g = 1.0;
   231     line_list.color.a = 1.0;
   233     for (
const costmap_converter::ObstacleMsg& obstacle : obstacles.obstacles)
   235       for (
int j=0; j< (int)obstacle.polygon.points.size()-1; ++j)
   237         geometry_msgs::Point line_start;
   238         line_start.x = obstacle.polygon.points[j].x;
   239         line_start.y = obstacle.polygon.points[j].y;
   240         line_list.points.push_back(line_start);
   241         geometry_msgs::Point line_end;
   242         line_end.x = obstacle.polygon.points[j+1].x;
   243         line_end.y = obstacle.polygon.points[j+1].y;
   244         line_list.points.push_back(line_end);
   247       if (!obstacle.polygon.points.empty() && obstacle.polygon.points.size() != 2 )
   249         geometry_msgs::Point line_start;
   250         line_start.x = obstacle.polygon.points.back().x;
   251         line_start.y = obstacle.polygon.points.back().y;
   252         line_list.points.push_back(line_start);
   253         if (line_list.points.size() % 2 != 0)
   255           geometry_msgs::Point line_end;
   256           line_end.x = obstacle.polygon.points.front().x;
   257           line_end.y = obstacle.polygon.points.front().y;
   258           line_list.points.push_back(line_end);
   285 int main(
int argc, 
char** argv)
   287   ros::init(argc, argv, 
"costmap_converter");
 void setCost(unsigned int mx, unsigned int my, unsigned char cost)
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
void publish(const boost::shared_ptr< M > &message) const 
void publishAsMarker(const std::string &frame_id, const costmap_converter::ObstacleArrayMsg &obstacles, ros::Publisher &marker_pub)
#define ROS_INFO_ONCE(...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > converter_
ros::Publisher obstacle_pub_
TFSIMD_FORCE_INLINE const tfScalar & y() const 
ROSCPP_DECL void spin(Spinner &spinner)
void costmapCallback(const nav_msgs::OccupancyGridConstPtr &msg)
ros::Subscriber costmap_sub_
void publishAsMarker(const std::string &frame_id, const std::vector< geometry_msgs::PolygonStamped > &polygonStamped, ros::Publisher &marker_pub)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > converter_loader_
TFSIMD_FORCE_INLINE const tfScalar & x() const 
CostmapStandaloneConversion()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getSizeInCellsY() const 
costmap_2d::Costmap2D map_
unsigned int getSizeInCellsX() const 
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
virtual void updateOrigin(double new_origin_x, double new_origin_y)
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const 
ros::Publisher marker_pub_
void costmapUpdateCallback(const map_msgs::OccupancyGridUpdateConstPtr &update)
double getResolution() const 
ros::Subscriber costmap_update_sub_