31 #include <sensor_msgs/PointCloud2.h> 32 #include <nav_msgs/OccupancyGrid.h> 33 #include <map_organizer_msgs/OccupancyGridArray.h> 35 #include <pcl/point_cloud.h> 36 #include <pcl/point_types.h> 68 pub_map_array_ = nh_.
advertise<map_organizer_msgs::OccupancyGridArray>(
"maps", 1,
true);
70 void cbPoints(
const sensor_msgs::PointCloud2::Ptr& msg)
72 pcl::PointCloud<pcl::PointXYZ>::Ptr pc(
new pcl::PointCloud<pcl::PointXYZ>());
77 double robot_height_f;
79 double floor_height_f;
81 double min_floor_area;
82 double floor_area_thresh_rate;
83 double floor_tolerance_f;
85 double points_thresh_rate;
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);
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;
103 for (
const auto& p : pc->points)
105 const int h = (p.z / grid);
106 const int x = (p.x / grid);
107 const int y = (p.y / grid);
120 if (hist.find(h) == hist.end())
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++)
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;
141 int hist_max = INT_MIN;
142 for (
const auto& h : hist)
143 if (h.second > hist_max)
146 min_points = hist_max * points_thresh_rate;
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++)
153 if (hist[i] > min_points)
155 for (
auto& p : pc->points)
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);
162 if (
abs(i - z) <= floor_height)
164 if (floor[i].find(v) == floor[i].end())
169 else if (i + floor_height + floor_tolerance < z && z <= i + robot_height)
176 for (
const auto& m : floor[i])
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];
193 const double floor_area_filter = floor_runnable_area_max * floor_area_thresh_rate;
195 for (
int i = min_height; i <= max_height; i++)
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]))
201 if (floor_runnable_area[i] > floor_area_filter)
203 nav_msgs::OccupancyGrid map;
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)
210 for (
const auto& m : floor[i])
212 int addr = (m.first.first - x_min) + (m.first.second - y_min) * mmd.width;
217 else if (m.second == 1)
218 map.data[addr] = 100;
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++)
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)
235 for (
size_t i = 0; i < it->data.size(); i++)
237 if (it->data[i] != 0 && it_prev->data[i] == 0)
240 it_prev->data[i] = -1;
242 else if (it->data[i] == 0 && it_prev->data[i] == 0)
244 it_prev->data[i] = -1;
248 for (
const auto c : it->data)
251 floor_runnable_area[h] = cnt * grid * grid;
253 for (
const auto c : it_prev->data)
256 floor_runnable_area[h_prev] = cnt_prev * grid * grid;
260 for (
int i = max_height; i >= min_height; i--)
262 printf(
" %6.2f ", i * grid);
263 for (
int j = 0; j <= 16; j++)
265 if (j <= hist[i] * 16 / hist_max)
270 if (floor_runnable_area[i] == 0.0)
271 printf(
" (%7d points)\n", hist[i]);
273 printf(
" (%7d points, %5.2f m^2 of floor)\n", hist[i], floor_runnable_area[i]);
277 map_organizer_msgs::OccupancyGridArray map_array;
278 for (
auto& map : maps)
281 int h = map.info.origin.position.z / grid;
282 if (floor_runnable_area[h] < min_floor_area)
284 ROS_WARN(
"floor %d (%5.2fm^2), h = %0.2fm skipped",
285 floor_num, floor_runnable_area[num], map.info.origin.position.z);
290 const auto map_cp = map.data;
291 for (
unsigned int i = 0; i < map_cp.size(); i++)
296 int floor_width = width;
297 for (
int xp = -width; xp <= width; xp++)
299 for (
int yp = -width; yp <= width; yp++)
301 int width_sq = xp * xp + yp * yp;
302 if (width_sq > width * width)
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)
308 const int addr = x + y * mmd.width;
309 if (map_cp[addr] == 100)
311 if (width_sq < floor_width * floor_width)
312 floor_width = sqrtf(width_sq);
317 for (
int xp = -floor_width; xp <= floor_width; xp++)
319 for (
int yp = -floor_width; yp <= floor_width; yp++)
321 if (xp * xp + yp * yp > floor_width * floor_width)
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)
327 const int addr = x + y * mmd.width;
328 if (map_cp[addr] != 100)
338 std::string name =
"map" + std::to_string(floor_num);
339 pub_maps_[name] = pnh_.
advertise<nav_msgs::OccupancyGrid>(name, 1,
true);
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);
346 pub_map_array_.
publish(map_array);
350 int main(
int argc,
char** argv)
352 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_
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
ros::Publisher pub_map_array_