42 #include <sensor_msgs/PointCloud2.h> 43 #include <nav_msgs/OccupancyGrid.h> 44 #include <map_organizer_msgs/OccupancyGridArray.h> 46 #include <pcl/point_cloud.h> 47 #include <pcl/point_types.h> 70 pub_map_array_ = nh_.
advertise<map_organizer_msgs::OccupancyGridArray>(
"maps", 1,
true);
72 void cbPoints(
const sensor_msgs::PointCloud2::Ptr& msg)
74 pcl::PointCloud<pcl::PointXYZ>::Ptr pc(
new pcl::PointCloud<pcl::PointXYZ>());
79 double robot_height_f;
81 double floor_height_f;
83 double min_floor_area;
84 double floor_area_thresh_rate;
85 double floor_tolerance_f;
87 double points_thresh_rate;
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);
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;
105 for (
const auto& p : pc->points)
107 const int h = (p.z / grid);
108 const int x = (p.x / grid);
109 const int y = (p.y / grid);
122 if (hist.find(h) == hist.end())
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++)
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;
143 int hist_max = std::numeric_limits<int>::lowest();
144 for (
const auto& h : hist)
145 if (h.second > hist_max)
148 min_points = hist_max * points_thresh_rate;
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++)
155 if (hist[i] > min_points)
157 for (
auto& p : pc->points)
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);
164 if (std::abs(i - z) <= floor_height)
166 if (floor[i].find(v) == floor[i].end())
171 else if (i + floor_height + floor_tolerance < z && z <= i + robot_height)
178 for (
const auto& m : floor[i])
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];
195 const double floor_area_filter = floor_runnable_area_max * floor_area_thresh_rate;
197 for (
int i = min_height; i <= max_height; i++)
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]))
203 if (floor_runnable_area[i] > floor_area_filter)
205 nav_msgs::OccupancyGrid map;
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)
212 for (
const auto& m : floor[i])
214 int addr = (m.first.first - x_min) + (m.first.second - y_min) * mmd.width;
219 else if (m.second == 1)
220 map.data[addr] = 100;
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++)
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)
237 for (
size_t i = 0; i < it->data.size(); i++)
239 if (it->data[i] != 0 && it_prev->data[i] == 0)
242 it_prev->data[i] = -1;
244 else if (it->data[i] == 0 && it_prev->data[i] == 0)
246 it_prev->data[i] = -1;
250 for (
const auto c : it->data)
253 floor_runnable_area[h] = cnt * grid * grid;
255 for (
const auto c : it_prev->data)
258 floor_runnable_area[h_prev] = cnt_prev * grid * grid;
262 for (
int i = max_height; i >= min_height; i--)
264 printf(
" %6.2f ", i * grid);
265 for (
int j = 0; j <= 16; j++)
267 if (j <= hist[i] * 16 / hist_max)
272 if (floor_runnable_area[i] == 0.0)
273 printf(
" (%7d points)\n", hist[i]);
275 printf(
" (%7d points, %5.2f m^2 of floor)\n", hist[i], floor_runnable_area[i]);
279 map_organizer_msgs::OccupancyGridArray map_array;
280 for (
auto& map : maps)
283 int h = map.info.origin.position.z / grid;
284 if (floor_runnable_area[h] < min_floor_area)
286 ROS_WARN(
"floor %d (%5.2fm^2), h = %0.2fm skipped",
287 floor_num, floor_runnable_area[num], map.info.origin.position.z);
292 const auto map_cp = map.data;
293 for (
unsigned int i = 0; i < map_cp.size(); i++)
298 int floor_width = width;
299 for (
int xp = -width; xp <= width; xp++)
301 for (
int yp = -width; yp <= width; yp++)
303 int width_sq = xp * xp + yp * yp;
304 if (width_sq > width * width)
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)
310 const int addr = x + y * mmd.width;
311 if (map_cp[addr] == 100)
313 if (width_sq < floor_width * floor_width)
314 floor_width = std::sqrt(width_sq);
319 for (
int xp = -floor_width; xp <= floor_width; xp++)
321 for (
int yp = -floor_width; yp <= floor_width; yp++)
323 if (xp * xp + yp * yp > floor_width * floor_width)
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)
329 const int addr = x + y * mmd.width;
330 if (map_cp[addr] != 100)
340 std::string name =
"map" + std::to_string(floor_num);
341 pub_maps_[name] = pnh_.
advertise<nav_msgs::OccupancyGrid>(name, 1,
true);
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);
348 pub_map_array_.
publish(map_array);
352 int main(
int argc,
char** argv)
354 ros::init(argc, argv,
"pointcloud_to_maps");
map_organizer_msgs::OccupancyGridArray maps
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_
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_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_