pointcloud_to_maps.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <sensor_msgs/PointCloud2.h>
32 #include <nav_msgs/OccupancyGrid.h>
33 #include <map_organizer_msgs/OccupancyGridArray.h>
34 
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
38 
39 #include <cmath>
40 #include <random>
41 #include <string>
42 #include <iostream>
43 #include <sstream>
44 #include <map>
45 #include <utility>
46 #include <vector>
47 
49 
51 {
52 private:
55  std::map<std::string, ros::Publisher> pub_maps_;
58 
59 public:
61  : pnh_("~")
62  , nh_()
63  {
66  nh_, "mapcloud",
67  pnh_, "map_cloud", 1, &PointcloudToMapsNode::cbPoints, this);
68  pub_map_array_ = nh_.advertise<map_organizer_msgs::OccupancyGridArray>("maps", 1, true);
69  }
70  void cbPoints(const sensor_msgs::PointCloud2::Ptr& msg)
71  {
72  pcl::PointCloud<pcl::PointXYZ>::Ptr pc(new pcl::PointCloud<pcl::PointXYZ>());
73  pcl::fromROSMsg(*msg, *pc);
74 
75  double grid;
76  int min_points;
77  double robot_height_f;
78  int robot_height;
79  double floor_height_f;
80  int floor_height;
81  double min_floor_area;
82  double floor_area_thresh_rate;
83  double floor_tolerance_f;
84  int floor_tolerance;
85  double points_thresh_rate;
86 
87  pnh_.param("grid", grid, 0.05);
88  pnh_.param("points_thresh_rate", points_thresh_rate, 0.5);
89  pnh_.param("robot_height", robot_height_f, 1.0);
90  pnh_.param("floor_height", floor_height_f, 0.1);
91  pnh_.param("floor_tolerance", floor_tolerance_f, 0.2);
92  pnh_.param("min_floor_area", min_floor_area, 100.0);
93  pnh_.param("floor_area_thresh_rate", floor_area_thresh_rate, 0.8);
94  robot_height = lroundf(robot_height_f / grid);
95  floor_height = lroundf(floor_height_f / grid);
96  floor_tolerance = lroundf(floor_tolerance_f / grid);
97 
98  std::map<int, int> hist;
99  int x_min = INT_MAX, x_max = 0;
100  int y_min = INT_MAX, y_max = 0;
101  int h_min = INT_MAX, h_max = 0;
102 
103  for (const auto& p : pc->points)
104  {
105  const int h = (p.z / grid);
106  const int x = (p.x / grid);
107  const int y = (p.y / grid);
108  if (x_min > x)
109  x_min = x;
110  if (y_min > y)
111  y_min = y;
112  if (h_min > h)
113  h_min = h;
114  if (x_max < x)
115  x_max = x;
116  if (y_max < y)
117  y_max = y;
118  if (h_max < h)
119  h_max = h;
120  if (hist.find(h) == hist.end())
121  hist[h] = 0;
122  hist[h]++;
123  }
124  const int max_height = h_max;
125  const int min_height = h_min;
126  std::map<int, float> floor_area;
127  std::map<int, float> floor_runnable_area;
128  for (int i = min_height; i <= max_height; i++)
129  floor_area[i] = 0;
130 
131  nav_msgs::MapMetaData mmd;
132  mmd.resolution = grid;
133  mmd.origin.position.x = x_min * grid;
134  mmd.origin.position.y = y_min * grid;
135  mmd.origin.orientation.w = 1.0;
136  mmd.width = x_max - x_min + 1;
137  mmd.height = y_max - y_min + 1;
138  ROS_INFO("width %d, height %d", mmd.width, mmd.height);
139  std::vector<nav_msgs::OccupancyGrid> maps;
140 
141  int hist_max = INT_MIN;
142  for (const auto& h : hist)
143  if (h.second > hist_max)
144  hist_max = h.second;
145 
146  min_points = hist_max * points_thresh_rate;
147 
148  double floor_area_max = 0;
149  double floor_runnable_area_max = 0;
150  std::map<int, std::map<std::pair<int, int>, char>> floor;
151  for (int i = min_height; i <= max_height; i++)
152  {
153  if (hist[i] > min_points)
154  {
155  for (auto& p : pc->points)
156  {
157  const int x = (p.x / grid);
158  const int y = (p.y / grid);
159  const int z = (p.z / grid);
160  const auto v = std::pair<int, int>(x, y);
161 
162  if (abs(i - z) <= floor_height)
163  {
164  if (floor[i].find(v) == floor[i].end())
165  {
166  floor[i][v] = 0;
167  }
168  }
169  else if (i + floor_height + floor_tolerance < z && z <= i + robot_height)
170  {
171  floor[i][v] = 1;
172  }
173  }
174 
175  int cnt = 0;
176  for (const auto& m : floor[i])
177  {
178  if (m.second == 0)
179  cnt++;
180  }
181  floor_runnable_area[i] = cnt * (grid * grid);
182  floor_area[i] = floor[i].size() * (grid * grid);
183  if (floor_area_max < floor_area[i])
184  floor_area_max = floor_area[i];
185  if (floor_runnable_area_max < floor_runnable_area[i])
186  floor_runnable_area_max = floor_runnable_area[i];
187  }
188  else
189  {
190  floor_area[i] = 0;
191  }
192  }
193  const double floor_area_filter = floor_runnable_area_max * floor_area_thresh_rate;
194  int map_num = 0;
195  for (int i = min_height; i <= max_height; i++)
196  {
197  if (hist[i] > min_points &&
198  (i == min_height || floor_runnable_area[i - 1] <= floor_runnable_area[i]) &&
199  (i == max_height || floor_runnable_area[i + 1] <= floor_runnable_area[i]))
200  {
201  if (floor_runnable_area[i] > floor_area_filter)
202  {
203  nav_msgs::OccupancyGrid map;
204  map.info = mmd;
205  map.info.origin.position.z = i * grid;
206  map.header = msg->header;
207  map.data.resize(mmd.width * mmd.height);
208  for (auto& c : map.data)
209  c = -1;
210  for (const auto& m : floor[i])
211  {
212  int addr = (m.first.first - x_min) + (m.first.second - y_min) * mmd.width;
213  if (m.second == 0)
214  {
215  map.data[addr] = 0;
216  }
217  else if (m.second == 1)
218  map.data[addr] = 100;
219  }
220 
221  maps.push_back(map);
222  map_num++;
223  }
224  }
225  }
226  ROS_INFO("Floor candidates: %d", map_num);
227  auto it_prev = maps.rbegin();
228  for (auto it = maps.rbegin() + 1; it != maps.rend() && it_prev != maps.rend(); it++)
229  {
230  const int h = it->info.origin.position.z / grid;
231  const int h_prev = it_prev->info.origin.position.z / grid;
232  if (fabs(it_prev->info.origin.position.z - it->info.origin.position.z) < grid * 1.5)
233  {
234  // merge slopes
235  for (size_t i = 0; i < it->data.size(); i++)
236  {
237  if (it->data[i] != 0 && it_prev->data[i] == 0)
238  {
239  it->data[i] = 0;
240  it_prev->data[i] = -1;
241  }
242  else if (it->data[i] == 0 && it_prev->data[i] == 0)
243  {
244  it_prev->data[i] = -1;
245  }
246  }
247  int cnt = 0;
248  for (const auto c : it->data)
249  if (c == 0)
250  ++cnt;
251  floor_runnable_area[h] = cnt * grid * grid;
252  int cnt_prev = 0;
253  for (const auto c : it_prev->data)
254  if (c == 0)
255  ++cnt_prev;
256  floor_runnable_area[h_prev] = cnt_prev * grid * grid;
257  }
258  it_prev = it;
259  }
260  for (int i = max_height; i >= min_height; i--)
261  {
262  printf(" %6.2f ", i * grid);
263  for (int j = 0; j <= 16; j++)
264  {
265  if (j <= hist[i] * 16 / hist_max)
266  printf("#");
267  else
268  printf(" ");
269  }
270  if (floor_runnable_area[i] == 0.0)
271  printf(" (%7d points)\n", hist[i]);
272  else
273  printf(" (%7d points, %5.2f m^2 of floor)\n", hist[i], floor_runnable_area[i]);
274  }
275  int num = -1;
276  int floor_num = 0;
277  map_organizer_msgs::OccupancyGridArray map_array;
278  for (auto& map : maps)
279  {
280  num++;
281  int h = map.info.origin.position.z / grid;
282  if (floor_runnable_area[h] < min_floor_area)
283  {
284  ROS_WARN("floor %d (%5.2fm^2), h = %0.2fm skipped",
285  floor_num, floor_runnable_area[num], map.info.origin.position.z);
286  continue;
287  }
288 
289  {
290  const auto map_cp = map.data;
291  for (unsigned int i = 0; i < map_cp.size(); i++)
292  {
293  if (map_cp[i] == 0)
294  {
295  const int width = 6;
296  int floor_width = width;
297  for (int xp = -width; xp <= width; xp++)
298  {
299  for (int yp = -width; yp <= width; yp++)
300  {
301  int width_sq = xp * xp + yp * yp;
302  if (width_sq > width * width)
303  continue;
304  const unsigned int x = i % mmd.width + xp;
305  const unsigned int y = i / mmd.width + yp;
306  if (x >= mmd.width || y >= mmd.height)
307  continue;
308  const int addr = x + y * mmd.width;
309  if (map_cp[addr] == 100)
310  {
311  if (width_sq < floor_width * floor_width)
312  floor_width = sqrtf(width_sq);
313  }
314  }
315  }
316  floor_width--;
317  for (int xp = -floor_width; xp <= floor_width; xp++)
318  {
319  for (int yp = -floor_width; yp <= floor_width; yp++)
320  {
321  if (xp * xp + yp * yp > floor_width * floor_width)
322  continue;
323  const unsigned int x = i % mmd.width + xp;
324  const unsigned int y = i / mmd.width + yp;
325  if (x >= mmd.width || y >= mmd.height)
326  continue;
327  const int addr = x + y * mmd.width;
328  if (map_cp[addr] != 100)
329  {
330  map.data[addr] = 0;
331  }
332  }
333  }
334  }
335  }
336  }
337 
338  std::string name = "map" + std::to_string(floor_num);
339  pub_maps_[name] = pnh_.advertise<nav_msgs::OccupancyGrid>(name, 1, true);
340  pub_maps_[name].publish(map);
341  map_array.maps.push_back(map);
342  ROS_WARN("floor %d (%5.2fm^2), h = %0.2fm",
343  floor_num, floor_runnable_area[h], map.info.origin.position.z);
344  floor_num++;
345  }
346  pub_map_array_.publish(map_array);
347  }
348 };
349 
350 int main(int argc, char** argv)
351 {
352  ros::init(argc, argv, "pointcloud_to_maps");
353 
355  ros::spin();
356 
357  return 0;
358 }
map_organizer_msgs::OccupancyGridArray maps
Definition: select_map.cpp:41
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
std::map< std::string, ros::Publisher > pub_maps_
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int main(int argc, char **argv)
void cbPoints(const sensor_msgs::PointCloud2::Ptr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Subscriber sub_points_
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
ros::Publisher pub_map_array_


map_organizer
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:56