costmap_converter_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann, Otniel Rinaldo
37  *********************************************************************/
38 
39 #include <ros/ros.h>
40 
41 #include <costmap_2d/costmap_2d.h>
42 #include <nav_msgs/OccupancyGrid.h>
43 #include <geometry_msgs/PolygonStamped.h>
44 #include <visualization_msgs/Marker.h>
45 
47 #include <pluginlib/class_loader.h>
48 
49 
50 
52 {
53 public:
54  CostmapStandaloneConversion() : converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), n_("~")
55  {
56  // load converter plugin from parameter server, otherwise set default
57  std::string converter_plugin = "costmap_converter::CostmapToPolygonsDBSMCCH";
58  n_.param("converter_plugin", converter_plugin, converter_plugin);
59 
60  try
61  {
62  converter_ = converter_loader_.createInstance(converter_plugin);
63  }
64  catch(const pluginlib::PluginlibException& ex)
65  {
66  ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what());
67  ros::shutdown();
68  }
69 
70  ROS_INFO_STREAM("Standalone costmap converter:" << converter_plugin << " loaded.");
71 
72  std::string costmap_topic = "/move_base/local_costmap/costmap";
73  n_.param("costmap_topic", costmap_topic, costmap_topic);
74 
75  std::string costmap_update_topic = "/move_base/local_costmap/costmap_updates";
76  n_.param("costmap_update_topic", costmap_update_topic, costmap_update_topic);
77 
78  std::string obstacles_topic = "costmap_obstacles";
79  n_.param("obstacles_topic", obstacles_topic, obstacles_topic);
80 
81  std::string polygon_marker_topic = "costmap_polygon_markers";
82  n_.param("polygon_marker_topic", polygon_marker_topic, polygon_marker_topic);
83 
86  obstacle_pub_ = n_.advertise<costmap_converter::ObstacleArrayMsg>(obstacles_topic, 1000);
87  marker_pub_ = n_.advertise<visualization_msgs::Marker>(polygon_marker_topic, 10);
88 
89  occupied_min_value_ = 100;
91 
92  std::string odom_topic = "/odom";
93  n_.param("odom_topic", odom_topic, odom_topic);
94 
95  if (converter_)
96  {
97  converter_->setOdomTopic(odom_topic);
98  converter_->initialize(n_);
99  converter_->setCostmap2D(&map_);
100  //converter_->startWorker(ros::Rate(5), &map, true);
101  }
102  }
103 
104 
105  void costmapCallback(const nav_msgs::OccupancyGridConstPtr& msg)
106  {
107  ROS_INFO_ONCE("Got first costmap callback. This message will be printed once");
108 
109  if (msg->info.width != map_.getSizeInCellsX() || msg->info.height != map_.getSizeInCellsY() || msg->info.resolution != map_.getResolution())
110  {
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);
113  }
114  else
115  {
116  map_.updateOrigin(msg->info.origin.position.x, msg->info.origin.position.y);
117  }
118 
119 
120  for (std::size_t i=0; i < msg->data.size(); ++i)
121  {
122  unsigned int mx, my;
123  map_.indexToCells((unsigned int)i, mx, my);
124  map_.setCost(mx, my, msg->data[i] >= occupied_min_value_ ? 255 : 0 );
125  }
126 
127  // convert
128  converter_->updateCostmap2D();
129  converter_->compute();
130  costmap_converter::ObstacleArrayConstPtr obstacles = converter_->getObstacles();
131 
132  if (!obstacles)
133  return;
134 
135  obstacle_pub_.publish(obstacles);
136 
137  publishAsMarker(msg->header.frame_id, *obstacles, marker_pub_);
138  }
139 
140  void costmapUpdateCallback(const map_msgs::OccupancyGridUpdateConstPtr& update)
141  {
142  unsigned int di = 0;
143  for (unsigned int y = 0; y < update->height ; ++y)
144  {
145  for (unsigned int x = 0; x < update->width ; ++x)
146  {
147  map_.setCost(x, y, update->data[di++] >= occupied_min_value_ ? 255 : 0 );
148  }
149  }
150 
151  // convert
152  // TODO(roesmann): currently, the converter updates the complete costmap and not the part which is updated in this callback
153  converter_->updateCostmap2D();
154  converter_->compute();
155  costmap_converter::ObstacleArrayConstPtr obstacles = converter_->getObstacles();
156 
157  if (!obstacles)
158  return;
159 
160  obstacle_pub_.publish(obstacles);
161 
162  publishAsMarker(update->header.frame_id, *obstacles, marker_pub_);
163  }
164 
165  void publishAsMarker(const std::string& frame_id, const std::vector<geometry_msgs::PolygonStamped>& polygonStamped, ros::Publisher& marker_pub)
166  {
167  visualization_msgs::Marker line_list;
168  line_list.header.frame_id = frame_id;
169  line_list.header.stamp = ros::Time::now();
170  line_list.ns = "Polygons";
171  line_list.action = visualization_msgs::Marker::ADD;
172  line_list.pose.orientation.w = 1.0;
173 
174  line_list.id = 0;
175  line_list.type = visualization_msgs::Marker::LINE_LIST;
176 
177  line_list.scale.x = 0.1;
178  line_list.color.g = 1.0;
179  line_list.color.a = 1.0;
180 
181  for (std::size_t i=0; i<polygonStamped.size(); ++i)
182  {
183  for (int j=0; j< (int)polygonStamped[i].polygon.points.size()-1; ++j)
184  {
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);
193  }
194  // close loop for current polygon
195  if (!polygonStamped[i].polygon.points.empty() && polygonStamped[i].polygon.points.size() != 2 )
196  {
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)
202  {
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);
207  }
208  }
209 
210 
211  }
212  marker_pub.publish(line_list);
213  }
214 
215  void publishAsMarker(const std::string& frame_id, const costmap_converter::ObstacleArrayMsg& obstacles, ros::Publisher& marker_pub)
216  {
217  visualization_msgs::Marker line_list;
218  line_list.header.frame_id = frame_id;
219  line_list.header.stamp = ros::Time::now();
220  line_list.ns = "Polygons";
221  line_list.action = visualization_msgs::Marker::ADD;
222  line_list.pose.orientation.w = 1.0;
223 
224  line_list.id = 0;
225  line_list.type = visualization_msgs::Marker::LINE_LIST;
226 
227  line_list.scale.x = 0.1;
228  line_list.color.g = 1.0;
229  line_list.color.a = 1.0;
230 
231  for (const costmap_converter::ObstacleMsg& obstacle : obstacles.obstacles)
232  {
233  for (int j=0; j< (int)obstacle.polygon.points.size()-1; ++j)
234  {
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);
243  }
244  // close loop for current polygon
245  if (!obstacle.polygon.points.empty() && obstacle.polygon.points.size() != 2 )
246  {
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)
252  {
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);
257  }
258  }
259 
260 
261  }
262  marker_pub.publish(line_list);
263  }
264 
265 private:
268 
274 
276 
278 
279 };
280 
281 
282 int main(int argc, char** argv)
283 {
284  ros::init(argc, argv, "costmap_converter");
285 
286  CostmapStandaloneConversion convert_process;
287 
288  ros::spin();
289 
290  return 0;
291 }
292 
293 
CostmapStandaloneConversion::n_
ros::NodeHandle n_
Definition: costmap_converter_node.cpp:305
CostmapStandaloneConversion
Definition: costmap_converter_node.cpp:51
CostmapStandaloneConversion::marker_pub_
ros::Publisher marker_pub_
Definition: costmap_converter_node.cpp:309
ros::Publisher
class_loader.h
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
costmap_2d.h
CostmapStandaloneConversion::obstacle_pub_
ros::Publisher obstacle_pub_
Definition: costmap_converter_node.cpp:308
ros::shutdown
ROSCPP_DECL void shutdown()
costmap_converter_interface.h
costmap_2d::Costmap2D
CostmapStandaloneConversion::converter_loader_
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > converter_loader_
Definition: costmap_converter_node.cpp:302
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
pluginlib::PluginlibException
CostmapStandaloneConversion::map_
costmap_2d::Costmap2D map_
Definition: costmap_converter_node.cpp:313
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
costmap_2d::Costmap2D::resizeMap
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
costmap_2d::Costmap2D::setCost
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
costmap_2d::Costmap2D::indexToCells
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
CostmapStandaloneConversion::costmapUpdateCallback
void costmapUpdateCallback(const map_msgs::OccupancyGridUpdateConstPtr &update)
Definition: costmap_converter_node.cpp:176
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons >
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
CostmapStandaloneConversion::converter_
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > converter_
Definition: costmap_converter_node.cpp:303
CostmapStandaloneConversion::publishAsMarker
void publishAsMarker(const std::string &frame_id, const std::vector< geometry_msgs::PolygonStamped > &polygonStamped, ros::Publisher &marker_pub)
Definition: costmap_converter_node.cpp:201
CostmapStandaloneConversion::costmapCallback
void costmapCallback(const nav_msgs::OccupancyGridConstPtr &msg)
Definition: costmap_converter_node.cpp:141
pluginlib::ClassLoader::createInstance
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
CostmapStandaloneConversion::costmap_update_sub_
ros::Subscriber costmap_update_sub_
Definition: costmap_converter_node.cpp:307
CostmapStandaloneConversion::costmap_sub_
ros::Subscriber costmap_sub_
Definition: costmap_converter_node.cpp:306
main
int main(int argc, char **argv)
Definition: costmap_converter_node.cpp:282
ROS_ERROR
#define ROS_ERROR(...)
CostmapStandaloneConversion::CostmapStandaloneConversion
CostmapStandaloneConversion()
Definition: costmap_converter_node.cpp:90
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
costmap_2d::Costmap2D::getResolution
double getResolution() const
costmap_2d::Costmap2D::updateOrigin
virtual void updateOrigin(double new_origin_x, double new_origin_y)
ros::spin
ROSCPP_DECL void spin()
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
ROS_INFO
#define ROS_INFO(...)
CostmapStandaloneConversion::occupied_min_value_
int occupied_min_value_
Definition: costmap_converter_node.cpp:311
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Fri Sep 20 2024 02:19:25