Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <ros/ros.h>
00040
00041 #include <costmap_2d/costmap_2d.h>
00042 #include <nav_msgs/OccupancyGrid.h>
00043 #include <geometry_msgs/PolygonStamped.h>
00044 #include <visualization_msgs/Marker.h>
00045
00046 #include <costmap_converter/costmap_converter_interface.h>
00047 #include <pluginlib/class_loader.h>
00048
00049
00050
00051 class CostmapStandaloneConversion
00052 {
00053 public:
00054 CostmapStandaloneConversion() : converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), n_("~")
00055 {
00056
00057 std::string converter_plugin = "costmap_converter::CostmapToPolygonsDBSMCCH";
00058 n_.param("converter_plugin", converter_plugin, converter_plugin);
00059
00060 try
00061 {
00062 converter_ = converter_loader_.createInstance(converter_plugin);
00063 }
00064 catch(pluginlib::PluginlibException& ex)
00065 {
00066 ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what());
00067 ros::shutdown();
00068 }
00069
00070 ROS_INFO_STREAM(converter_plugin << " loaded.");
00071
00072 std::string costmap_topic = "move_base/local_costmap/costmap";
00073 n_.param("costmap_topic", costmap_topic, costmap_topic);
00074
00075 std::string obstacles_topic = "costmap_obstacles";
00076 n_.param("obstacles_topic", obstacles_topic, obstacles_topic);
00077
00078 std::string polygon_marker_topic = "costmap_polygon_markers";
00079 n_.param("polygon_marker_topic", polygon_marker_topic, polygon_marker_topic);
00080
00081 costmap_sub_ = n_.subscribe(costmap_topic, 1, &CostmapStandaloneConversion::costmapCallback, this);
00082 obstacle_pub_ = n_.advertise<costmap_converter::ObstacleArrayMsg>(obstacles_topic, 1000);
00083 marker_pub_ = n_.advertise<visualization_msgs::Marker>(polygon_marker_topic, 10);
00084
00085 frame_id_ = "/map";
00086 n_.param("frame_id", frame_id_, frame_id_);
00087
00088 occupied_min_value_ = 100;
00089 n_.param("occupied_min_value", occupied_min_value_, occupied_min_value_);
00090
00091 std::string odom_topic = "/odom";
00092 n_.param("odom_topic", odom_topic, odom_topic);
00093
00094 if (converter_)
00095 {
00096 converter_->setOdomTopic(odom_topic);
00097 converter_->initialize(n_);
00098 converter_->setCostmap2D(&map);
00099
00100 }
00101 }
00102
00103
00104 void costmapCallback(const nav_msgs::OccupancyGridConstPtr& msg)
00105 {
00106 ROS_INFO_ONCE("Got first costmap callback. This message will be printed once");
00107
00108 if (msg->info.width != map.getSizeInCellsX() || msg->info.height != map.getSizeInCellsY() || msg->info.resolution != map.getResolution())
00109 {
00110 ROS_INFO("New map format, resizing and resetting map...");
00111 map.resizeMap(msg->info.width, msg->info.height, msg->info.resolution, msg->info.origin.position.x, msg->info.origin.position.y);
00112 }
00113 else
00114 {
00115 map.updateOrigin(msg->info.origin.position.x, msg->info.origin.position.y);
00116 }
00117
00118
00119 for (std::size_t i=0; i < msg->data.size(); ++i)
00120 {
00121 unsigned int mx, my;
00122 map.indexToCells((unsigned int)i, mx, my);
00123 map.setCost(mx, my, msg->data[i] >= occupied_min_value_ ? 255 : 0 );
00124 }
00125
00126
00127 converter_->updateCostmap2D();
00128 converter_->compute();
00129 costmap_converter::ObstacleArrayConstPtr obstacles = converter_->getObstacles();
00130
00131 if (!obstacles)
00132 return;
00133
00134 obstacle_pub_.publish(obstacles);
00135
00136 publishAsMarker(msg->header.frame_id, *obstacles, marker_pub_);
00137
00138 }
00139
00140 void publishAsMarker(const std::string& frame_id, const std::vector<geometry_msgs::PolygonStamped>& polygonStamped, ros::Publisher& marker_pub)
00141 {
00142 visualization_msgs::Marker line_list;
00143 line_list.header.frame_id = frame_id;
00144 line_list.header.stamp = ros::Time::now();
00145 line_list.ns = "Polygons";
00146 line_list.action = visualization_msgs::Marker::ADD;
00147 line_list.pose.orientation.w = 1.0;
00148
00149 line_list.id = 0;
00150 line_list.type = visualization_msgs::Marker::LINE_LIST;
00151
00152 line_list.scale.x = 0.1;
00153 line_list.color.g = 1.0;
00154 line_list.color.a = 1.0;
00155
00156 for (std::size_t i=0; i<polygonStamped.size(); ++i)
00157 {
00158 for (int j=0; j< (int)polygonStamped[i].polygon.points.size()-1; ++j)
00159 {
00160 geometry_msgs::Point line_start;
00161 line_start.x = polygonStamped[i].polygon.points[j].x;
00162 line_start.y = polygonStamped[i].polygon.points[j].y;
00163 line_list.points.push_back(line_start);
00164 geometry_msgs::Point line_end;
00165 line_end.x = polygonStamped[i].polygon.points[j+1].x;
00166 line_end.y = polygonStamped[i].polygon.points[j+1].y;
00167 line_list.points.push_back(line_end);
00168 }
00169
00170 if (!polygonStamped[i].polygon.points.empty() && polygonStamped[i].polygon.points.size() != 2 )
00171 {
00172 geometry_msgs::Point line_start;
00173 line_start.x = polygonStamped[i].polygon.points.back().x;
00174 line_start.y = polygonStamped[i].polygon.points.back().y;
00175 line_list.points.push_back(line_start);
00176 if (line_list.points.size() % 2 != 0)
00177 {
00178 geometry_msgs::Point line_end;
00179 line_end.x = polygonStamped[i].polygon.points.front().x;
00180 line_end.y = polygonStamped[i].polygon.points.front().y;
00181 line_list.points.push_back(line_end);
00182 }
00183 }
00184
00185
00186 }
00187 marker_pub.publish(line_list);
00188 }
00189
00190 void publishAsMarker(const std::string& frame_id, const costmap_converter::ObstacleArrayMsg& obstacles, ros::Publisher& marker_pub)
00191 {
00192 visualization_msgs::Marker line_list;
00193 line_list.header.frame_id = frame_id;
00194 line_list.header.stamp = ros::Time::now();
00195 line_list.ns = "Polygons";
00196 line_list.action = visualization_msgs::Marker::ADD;
00197 line_list.pose.orientation.w = 1.0;
00198
00199 line_list.id = 0;
00200 line_list.type = visualization_msgs::Marker::LINE_LIST;
00201
00202 line_list.scale.x = 0.1;
00203 line_list.color.g = 1.0;
00204 line_list.color.a = 1.0;
00205
00206 for (const costmap_converter::ObstacleMsg& obstacle : obstacles.obstacles)
00207 {
00208 for (int j=0; j< (int)obstacle.polygon.points.size()-1; ++j)
00209 {
00210 geometry_msgs::Point line_start;
00211 line_start.x = obstacle.polygon.points[j].x;
00212 line_start.y = obstacle.polygon.points[j].y;
00213 line_list.points.push_back(line_start);
00214 geometry_msgs::Point line_end;
00215 line_end.x = obstacle.polygon.points[j+1].x;
00216 line_end.y = obstacle.polygon.points[j+1].y;
00217 line_list.points.push_back(line_end);
00218 }
00219
00220 if (!obstacle.polygon.points.empty() && obstacle.polygon.points.size() != 2 )
00221 {
00222 geometry_msgs::Point line_start;
00223 line_start.x = obstacle.polygon.points.back().x;
00224 line_start.y = obstacle.polygon.points.back().y;
00225 line_list.points.push_back(line_start);
00226 if (line_list.points.size() % 2 != 0)
00227 {
00228 geometry_msgs::Point line_end;
00229 line_end.x = obstacle.polygon.points.front().x;
00230 line_end.y = obstacle.polygon.points.front().y;
00231 line_list.points.push_back(line_end);
00232 }
00233 }
00234
00235
00236 }
00237 marker_pub.publish(line_list);
00238 }
00239
00240 private:
00241 pluginlib::ClassLoader<costmap_converter::BaseCostmapToPolygons> converter_loader_;
00242 boost::shared_ptr<costmap_converter::BaseCostmapToPolygons> converter_;
00243
00244 ros::NodeHandle n_;
00245 ros::Subscriber costmap_sub_;
00246 ros::Publisher obstacle_pub_;
00247 ros::Publisher marker_pub_;
00248
00249 std::string frame_id_;
00250 int occupied_min_value_;
00251
00252 costmap_2d::Costmap2D map;
00253
00254 };
00255
00256
00257 int main(int argc, char** argv)
00258 {
00259 ros::init(argc, argv, "costmap_converter");
00260
00261 CostmapStandaloneConversion convert_process;
00262
00263 ros::spin();
00264
00265 costmap_2d::Costmap2D costmap;
00266
00267 return 0;
00268 }
00269
00270