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 <cmath>
31 #include <iostream>
32 #include <limits>
33 #include <map>
34 #include <random>
35 #include <sstream>
36 #include <string>
37 #include <utility>
38 #include <vector>
39 
40 #include <ros/ros.h>
41 
42 #include <sensor_msgs/PointCloud2.h>
43 #include <nav_msgs/OccupancyGrid.h>
44 #include <map_organizer_msgs/OccupancyGridArray.h>
45 
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
49 
51 
53 {
54 private:
57  std::map<std::string, ros::Publisher> pub_maps_;
60 
61 public:
63  : pnh_("~")
64  , nh_()
65  {
68  nh_, "mapcloud",
69  pnh_, "map_cloud", 1, &PointcloudToMapsNode::cbPoints, this);
70  pub_map_array_ = nh_.advertise<map_organizer_msgs::OccupancyGridArray>("maps", 1, true);
71  }
72  void cbPoints(const sensor_msgs::PointCloud2::Ptr& msg)
73  {
74  pcl::PointCloud<pcl::PointXYZ>::Ptr pc(new pcl::PointCloud<pcl::PointXYZ>());
75  pcl::fromROSMsg(*msg, *pc);
76 
77  double grid;
78  int min_points;
79  double robot_height_f;
80  int robot_height;
81  double floor_height_f;
82  int floor_height;
83  double min_floor_area;
84  double floor_area_thresh_rate;
85  double floor_tolerance_f;
86  int floor_tolerance;
87  double points_thresh_rate;
88 
89  pnh_.param("grid", grid, 0.05);
90  pnh_.param("points_thresh_rate", points_thresh_rate, 0.5);
91  pnh_.param("robot_height", robot_height_f, 1.0);
92  pnh_.param("floor_height", floor_height_f, 0.1);
93  pnh_.param("floor_tolerance", floor_tolerance_f, 0.2);
94  pnh_.param("min_floor_area", min_floor_area, 100.0);
95  pnh_.param("floor_area_thresh_rate", floor_area_thresh_rate, 0.8);
96  robot_height = std::lround(robot_height_f / grid);
97  floor_height = std::lround(floor_height_f / grid);
98  floor_tolerance = std::lround(floor_tolerance_f / grid);
99 
100  std::map<int, int> hist;
101  int x_min = std::numeric_limits<int>::max(), x_max = 0;
102  int y_min = std::numeric_limits<int>::max(), y_max = 0;
103  int h_min = std::numeric_limits<int>::max(), h_max = 0;
104 
105  for (const auto& p : pc->points)
106  {
107  const int h = (p.z / grid);
108  const int x = (p.x / grid);
109  const int y = (p.y / grid);
110  if (x_min > x)
111  x_min = x;
112  if (y_min > y)
113  y_min = y;
114  if (h_min > h)
115  h_min = h;
116  if (x_max < x)
117  x_max = x;
118  if (y_max < y)
119  y_max = y;
120  if (h_max < h)
121  h_max = h;
122  if (hist.find(h) == hist.end())
123  hist[h] = 0;
124  hist[h]++;
125  }
126  const int max_height = h_max;
127  const int min_height = h_min;
128  std::map<int, float> floor_area;
129  std::map<int, float> floor_runnable_area;
130  for (int i = min_height; i <= max_height; i++)
131  floor_area[i] = 0;
132 
133  nav_msgs::MapMetaData mmd;
134  mmd.resolution = grid;
135  mmd.origin.position.x = x_min * grid;
136  mmd.origin.position.y = y_min * grid;
137  mmd.origin.orientation.w = 1.0;
138  mmd.width = x_max - x_min + 1;
139  mmd.height = y_max - y_min + 1;
140  ROS_INFO("width %d, height %d", mmd.width, mmd.height);
141  std::vector<nav_msgs::OccupancyGrid> maps;
142 
143  int hist_max = std::numeric_limits<int>::lowest();
144  for (const auto& h : hist)
145  if (h.second > hist_max)
146  hist_max = h.second;
147 
148  min_points = hist_max * points_thresh_rate;
149 
150  double floor_area_max = 0;
151  double floor_runnable_area_max = 0;
152  std::map<int, std::map<std::pair<int, int>, char>> floor;
153  for (int i = min_height; i <= max_height; i++)
154  {
155  if (hist[i] > min_points)
156  {
157  for (auto& p : pc->points)
158  {
159  const int x = (p.x / grid);
160  const int y = (p.y / grid);
161  const int z = (p.z / grid);
162  const auto v = std::pair<int, int>(x, y);
163 
164  if (std::abs(i - z) <= floor_height)
165  {
166  if (floor[i].find(v) == floor[i].end())
167  {
168  floor[i][v] = 0;
169  }
170  }
171  else if (i + floor_height + floor_tolerance < z && z <= i + robot_height)
172  {
173  floor[i][v] = 1;
174  }
175  }
176 
177  int cnt = 0;
178  for (const auto& m : floor[i])
179  {
180  if (m.second == 0)
181  cnt++;
182  }
183  floor_runnable_area[i] = cnt * (grid * grid);
184  floor_area[i] = floor[i].size() * (grid * grid);
185  if (floor_area_max < floor_area[i])
186  floor_area_max = floor_area[i];
187  if (floor_runnable_area_max < floor_runnable_area[i])
188  floor_runnable_area_max = floor_runnable_area[i];
189  }
190  else
191  {
192  floor_area[i] = 0;
193  }
194  }
195  const double floor_area_filter = floor_runnable_area_max * floor_area_thresh_rate;
196  int map_num = 0;
197  for (int i = min_height; i <= max_height; i++)
198  {
199  if (hist[i] > min_points &&
200  (i == min_height || floor_runnable_area[i - 1] <= floor_runnable_area[i]) &&
201  (i == max_height || floor_runnable_area[i + 1] <= floor_runnable_area[i]))
202  {
203  if (floor_runnable_area[i] > floor_area_filter)
204  {
205  nav_msgs::OccupancyGrid map;
206  map.info = mmd;
207  map.info.origin.position.z = i * grid;
208  map.header = msg->header;
209  map.data.resize(mmd.width * mmd.height);
210  for (auto& c : map.data)
211  c = -1;
212  for (const auto& m : floor[i])
213  {
214  int addr = (m.first.first - x_min) + (m.first.second - y_min) * mmd.width;
215  if (m.second == 0)
216  {
217  map.data[addr] = 0;
218  }
219  else if (m.second == 1)
220  map.data[addr] = 100;
221  }
222 
223  maps.push_back(map);
224  map_num++;
225  }
226  }
227  }
228  ROS_INFO("Floor candidates: %d", map_num);
229  auto it_prev = maps.rbegin();
230  for (auto it = maps.rbegin() + 1; it != maps.rend() && it_prev != maps.rend(); it++)
231  {
232  const int h = it->info.origin.position.z / grid;
233  const int h_prev = it_prev->info.origin.position.z / grid;
234  if (std::abs(it_prev->info.origin.position.z - it->info.origin.position.z) < grid * 1.5)
235  {
236  // merge slopes
237  for (size_t i = 0; i < it->data.size(); i++)
238  {
239  if (it->data[i] != 0 && it_prev->data[i] == 0)
240  {
241  it->data[i] = 0;
242  it_prev->data[i] = -1;
243  }
244  else if (it->data[i] == 0 && it_prev->data[i] == 0)
245  {
246  it_prev->data[i] = -1;
247  }
248  }
249  int cnt = 0;
250  for (const auto c : it->data)
251  if (c == 0)
252  ++cnt;
253  floor_runnable_area[h] = cnt * grid * grid;
254  int cnt_prev = 0;
255  for (const auto c : it_prev->data)
256  if (c == 0)
257  ++cnt_prev;
258  floor_runnable_area[h_prev] = cnt_prev * grid * grid;
259  }
260  it_prev = it;
261  }
262  for (int i = max_height; i >= min_height; i--)
263  {
264  printf(" %6.2f ", i * grid);
265  for (int j = 0; j <= 16; j++)
266  {
267  if (j <= hist[i] * 16 / hist_max)
268  printf("#");
269  else
270  printf(" ");
271  }
272  if (floor_runnable_area[i] == 0.0)
273  printf(" (%7d points)\n", hist[i]);
274  else
275  printf(" (%7d points, %5.2f m^2 of floor)\n", hist[i], floor_runnable_area[i]);
276  }
277  int num = -1;
278  int floor_num = 0;
279  map_organizer_msgs::OccupancyGridArray map_array;
280  for (auto& map : maps)
281  {
282  num++;
283  int h = map.info.origin.position.z / grid;
284  if (floor_runnable_area[h] < min_floor_area)
285  {
286  ROS_WARN("floor %d (%5.2fm^2), h = %0.2fm skipped",
287  floor_num, floor_runnable_area[num], map.info.origin.position.z);
288  continue;
289  }
290 
291  {
292  const auto map_cp = map.data;
293  for (unsigned int i = 0; i < map_cp.size(); i++)
294  {
295  if (map_cp[i] == 0)
296  {
297  const int width = 6;
298  int floor_width = width;
299  for (int xp = -width; xp <= width; xp++)
300  {
301  for (int yp = -width; yp <= width; yp++)
302  {
303  int width_sq = xp * xp + yp * yp;
304  if (width_sq > width * width)
305  continue;
306  const unsigned int x = i % mmd.width + xp;
307  const unsigned int y = i / mmd.width + yp;
308  if (x >= mmd.width || y >= mmd.height)
309  continue;
310  const int addr = x + y * mmd.width;
311  if (map_cp[addr] == 100)
312  {
313  if (width_sq < floor_width * floor_width)
314  floor_width = std::sqrt(width_sq);
315  }
316  }
317  }
318  floor_width--;
319  for (int xp = -floor_width; xp <= floor_width; xp++)
320  {
321  for (int yp = -floor_width; yp <= floor_width; yp++)
322  {
323  if (xp * xp + yp * yp > floor_width * floor_width)
324  continue;
325  const unsigned int x = i % mmd.width + xp;
326  const unsigned int y = i / mmd.width + yp;
327  if (x >= mmd.width || y >= mmd.height)
328  continue;
329  const int addr = x + y * mmd.width;
330  if (map_cp[addr] != 100)
331  {
332  map.data[addr] = 0;
333  }
334  }
335  }
336  }
337  }
338  }
339 
340  std::string name = "map" + std::to_string(floor_num);
341  pub_maps_[name] = pnh_.advertise<nav_msgs::OccupancyGrid>(name, 1, true);
342  pub_maps_[name].publish(map);
343  map_array.maps.push_back(map);
344  ROS_WARN("floor %d (%5.2fm^2), h = %0.2fm",
345  floor_num, floor_runnable_area[h], map.info.origin.position.z);
346  floor_num++;
347  }
348  pub_map_array_.publish(map_array);
349  }
350 };
351 
352 int main(int argc, char** argv)
353 {
354  ros::init(argc, argv, "pointcloud_to_maps");
355 
357  ros::spin();
358 
359  return 0;
360 }
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_
ros::Publisher pub_map_array_


map_organizer
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:33