hector_costmap.cpp
Go to the documentation of this file.
2 
3 // compute linear index for given map coords
4 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
5 
6 #define OCCUPIED_CELL 100
7 #define FREE_CELL 0
8 #define UNKNOWN_CELL -1
9 
10 #define GRID_MAP 1
11 #define CLOUD_MAP 2
12 #define ELEVATION_MAP 4
13 
14 #define USE_GRID_MAP_ONLY GRID_MAP
15 #define USE_ELEVATION_MAP_ONLY ELEVATION_MAP
16 #define USE_GRID_AND_ELEVATION_MAP (GRID_MAP | ELEVATION_MAP)
17 #define USE_GRID_AND_CLOUD_MAP (GRID_MAP | CLOUD_MAP)
18 #define USE_GRID_AND_ELEVATION_MAP_AND_CLOUD_MAP (GRID_MAP | CLOUD_MAP | ELEVATION_MAP)
19 
20 
21 CostMapCalculation::CostMapCalculation() : nHandle(), pnHandle("~")
22 {
23  int width, height;
24  double grid_res_xy;
25 
26  pnHandle.param("elevation_resolution", grid_res_z, 0.01); //[m]
27 
28  pnHandle.param("max_grid_size_x", width, 1024); //[cell]
29  cost_map.info.width = width;
30  pnHandle.param("max_grid_size_y", height, 1024); //[cell]
31  cost_map.info.height = height;
32  pnHandle.param("map_resolution", grid_res_xy, 0.05); //[m]
33  cost_map.info.resolution = grid_res_xy;
34  pnHandle.param("origin_x",cost_map.info.origin.position.x, -(double)cost_map.info.width*(double)cost_map.info.resolution/2.0); //[m]
35  pnHandle.param("origin_y",cost_map.info.origin.position.y, -(double)cost_map.info.height*(double)cost_map.info.resolution/2.0); //[m]
36  pnHandle.param("origin_z",cost_map.info.origin.position.z, 0.0); //[m]
37  pnHandle.param("orientation_x",cost_map.info.origin.orientation.x, 0.0); //[]
38  pnHandle.param("orientation_y",cost_map.info.origin.orientation.y, 0.0); //[]
39  pnHandle.param("orientation_z",cost_map.info.origin.orientation.z, 0.0); //[]
40  pnHandle.param("orientation_w",cost_map.info.origin.orientation.w, 1.0); //[]
41 
42  pnHandle.param("initial_free_cells_radius", initial_free_cells_radius, 0.30); //[m]
43  pnHandle.param("update_radius", update_radius_world, 4.0); //[m]
44  pnHandle.param("max_delta_elevation", max_delta_elevation, 0.08); //[m]
45 
46  pnHandle.param("map_frame_id", map_frame_id,std::string("map"));
47  pnHandle.param("local_transform_frame_id", local_transform_frame_id,std::string("base_footprint"));
48  pnHandle.param("cost_map_topic", cost_map_topic, std::string("cost_map"));
49  pnHandle.param("elevation_map_topic", elevation_map_topic, std::string("elevation_map_local"));
50  pnHandle.param("grid_map_topic", grid_map_topic, std::string("scanmatcher_map"));
51 
52  pnHandle.param("use_elevation_map", use_elevation_map, true);
53  pnHandle.param("use_grid_map", use_grid_map, true);
54  pnHandle.param("use_cloud_map", use_cloud_map, false);
55  pnHandle.param("allow_elevation_map_to_clear_occupied_cells", allow_elevation_map_to_clear_occupied_cells, true);
56  pnHandle.param("max_clear_size", max_clear_size, 2);
57 
58  pnHandle.param("point_cloud_topic", point_cloud_topic,std::string("openni/depth/points"));
59  pnHandle.param("slize_min_height", slize_min_height, 0.30); //[m]
60  pnHandle.param("slize_max_height", slize_min_height, 0.35); //[m]
61 
62  pnHandle.param("costmap_pub_freq", costmap_pub_freq, 4.0); //[Hz]
63 
64  pnHandle.param("sys_msg_topic", sys_msg_topic, std::string("syscommand"));
65 
66  cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
67  elevation_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
68  cloud_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
69 
70  world_map_transform.setTransforms(cost_map.info);
71 
72  // loop through starting area
73  min_index(0) = cost_map.info.width/2-floor(initial_free_cells_radius/cost_map.info.resolution);
74  min_index(1) = cost_map.info.height/2-floor(initial_free_cells_radius/cost_map.info.resolution);
75  max_index(0) = cost_map.info.width/2+floor(initial_free_cells_radius/cost_map.info.resolution);
76  max_index(1) = cost_map.info.height/2+floor(initial_free_cells_radius/cost_map.info.resolution);
77  for (int v = min_index(1); v < max_index(1); ++v)
78  for (int u = min_index(0); u < max_index(0); ++u)
79  cost_map.data[MAP_IDX(cost_map.info.width, u, v)] = FREE_CELL;
80 
81  pub_cost_map = nHandle.advertise<nav_msgs::OccupancyGrid>(cost_map_topic, 1, true);
82 
83  received_elevation_map = false;
84  received_grid_map = false;
85  received_point_cloud = false;
86 
87  sliced_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
88 
91 
92  if(use_grid_map)
94 
95  if(use_cloud_map)
97 
99 
101  dyn_rec_server_.setCallback(boost::bind(&CostMapCalculation::dynRecParamCallback, this, _1, _2));
102 
104 
105  ROS_INFO("HectorCM: is up and running.");
106 
107  pub_cloud_slice = pnHandle.advertise<sensor_msgs::PointCloud2>("cloud_slice",1,true);
108 
109  ros::spin();
110 }
111 
112 
114 {
115  ROS_INFO("HectorCM: Shutting down!");
116 }
117 
118 
119 void CostMapCalculation::sysMessageCallback(const std_msgs::String& string)
120 {
121  ROS_DEBUG("HectorCM: sysMsgCallback, msg contents: %s", string.data.c_str());
122 
123  if (string.data == "reset")
124  {
125  ROS_INFO("HectorCM: reset");
126 
127  // set default values
128  cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
129  elevation_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
130  cloud_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
131 
132  // loop through starting area
133  min_index(0) = cost_map.info.width/2-floor(initial_free_cells_radius/cost_map.info.resolution);
134  min_index(1) = cost_map.info.height/2-floor(initial_free_cells_radius/cost_map.info.resolution);
135  max_index(0) = cost_map.info.width/2+floor(initial_free_cells_radius/cost_map.info.resolution);
136  max_index(1) = cost_map.info.height/2+floor(initial_free_cells_radius/cost_map.info.resolution);
137  for (int v = min_index(1); v < max_index(1); ++v)
138  for (int u = min_index(0); u < max_index(0); ++u)
139  cost_map.data[MAP_IDX(cost_map.info.width, u, v)] = FREE_CELL;
140 
141  received_elevation_map = false;
142  received_grid_map = false;
143  received_point_cloud = false;
144  }
145 }
146 
147 
148 void CostMapCalculation::dynRecParamCallback(hector_costmap::CostMapCalculationConfig &config, uint32_t level)
149 {
150  max_delta_elevation = config.max_delta_elevation;
151  allow_elevation_map_to_clear_occupied_cells = config.allow_elevation_map_to_clear_occupied_cells;
152  max_clear_size = config.max_clear_size;
153  slize_min_height = config.slize_min_height;
154  slize_max_height = config.slize_max_height;
155  update_radius_world = config.update_radius_world;
156 }
157 
158 
159 void CostMapCalculation::updateMapParamsCallback(const nav_msgs::MapMetaData& map_meta_data)
160 {
161  ROS_DEBUG("HectorCM: received new map meta data -> overwrite old parameters");
162 
163  // check if new parameters differ and abort otherwise
164  if (cost_map.info.width == map_meta_data.width &&
165  cost_map.info.height == map_meta_data.height &&
166  cost_map.info.resolution == map_meta_data.resolution &&
167  cost_map.info.origin.position.x == map_meta_data.origin.position.x &&
168  cost_map.info.origin.position.y == map_meta_data.origin.position.y &&
169  cost_map.info.origin.position.z == map_meta_data.origin.position.z &&
170  cost_map.info.origin.orientation.x == map_meta_data.origin.orientation.x &&
171  cost_map.info.origin.orientation.y == map_meta_data.origin.orientation.y &&
172  cost_map.info.origin.orientation.z == map_meta_data.origin.orientation.z &&
173  cost_map.info.origin.orientation.w == map_meta_data.origin.orientation.w) {
174  return;
175  }
176 
177  // set new parameters
178  cost_map.info.width = map_meta_data.width;
179  cost_map.info.height = map_meta_data.height;
180  cost_map.info.resolution = map_meta_data.resolution;
181 
182  cost_map.info.origin.position.x = map_meta_data.origin.position.x;
183  cost_map.info.origin.position.y = map_meta_data.origin.position.y;
184  cost_map.info.origin.position.z = map_meta_data.origin.position.z;
185 
186  cost_map.info.origin.orientation.x = map_meta_data.origin.orientation.x;
187  cost_map.info.origin.orientation.y = map_meta_data.origin.orientation.y;
188  cost_map.info.origin.orientation.z = map_meta_data.origin.orientation.z;
189  cost_map.info.origin.orientation.w = map_meta_data.origin.orientation.w;
190 
191  world_map_transform.setTransforms(cost_map.info);
192 
193  // allocate memory
194  cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
195  elevation_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
196  cloud_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
197 
198  // loop through starting area
199  min_index(0) = cost_map.info.width/2-floor(initial_free_cells_radius/cost_map.info.resolution);
200  min_index(1) = cost_map.info.height/2-floor(initial_free_cells_radius/cost_map.info.resolution);
201  max_index(0) = cost_map.info.width/2+floor(initial_free_cells_radius/cost_map.info.resolution);
202  max_index(1) = cost_map.info.height/2+floor(initial_free_cells_radius/cost_map.info.resolution);
203  for (int v = min_index(1); v < max_index(1); ++v)
204  for (int u = min_index(0); u < max_index(0); ++u)
205  cost_map.data[MAP_IDX(cost_map.info.width, u, v)] = FREE_CELL;
206 
207  // update flags
208  received_elevation_map = false;
209  received_grid_map = false;
210  use_cloud_map = false;
211 }
212 
214 {
215  ROS_DEBUG("HectorCM: published a new costmap");
216 
217  // set the header information on the map
218  cost_map.header.stamp = ros::Time::now();
219  cost_map.header.frame_id = map_frame_id;
220 
222 }
223 
224 
225 void CostMapCalculation::callbackElevationMap(const hector_elevation_msgs::ElevationGridConstPtr& elevation_map_msg)
226 {
227  ROS_DEBUG("HectorCM: received new elevation map");
228 
229  // check header
230  if((int)(1000*elevation_map_msg->info.resolution_xy) != (int)(1000*cost_map.info.resolution) && // Magic number 1000 -> min grid size should not be less than 1mm
231  elevation_map_msg->info.height != cost_map.info.height &&
232  elevation_map_msg->info.width != cost_map.info.width)
233  {
234  ROS_ERROR("HectorCM: elevation map resolution and or size incorrect!");
235  return;
236  }
237 
238  // store elevation_map_msg in local variable
239  elevation_map_ = cv::Mat(elevation_map_msg->info.height, elevation_map_msg->info.width, CV_16S, const_cast<int16_t*>(&elevation_map_msg->data[0]), 2*(size_t)elevation_map_msg->info.width);
240 
241  // store elevation map zero level
242  elevation_zero_level = elevation_map_msg->info.zero_elevation;
243 
244  // compute region of intereset
245  if(!computeWindowIndices(elevation_map_msg->header.stamp, update_radius_world))
246  return;
247 
248  // loop through each element
249  int filtered_cell, filtered_cell_x, filtered_cell_y;
250  for (int v = min_index(1); v < max_index(1); ++v)
251  {
252  for (int u = min_index(0); u < max_index(0); ++u)
253  {
254  // compute cost_map_index
255  unsigned int cost_map_index = MAP_IDX(cost_map.info.width, u, v);
256 
257  // check if neighbouring cells are known
258  if(elevation_map_.at<int16_t>(v+1,u) == (-elevation_zero_level) ||
259  elevation_map_.at<int16_t>(v-1,u) == (-elevation_zero_level) ||
260  elevation_map_.at<int16_t>(v,u+1) == (-elevation_zero_level) ||
261  elevation_map_.at<int16_t>(v,u-1) == (-elevation_zero_level))
262  continue;
263 
264  // edge filter
265  filtered_cell_y = abs(elevation_map_.at<int16_t>(v,u-1) - elevation_map_.at<int16_t>(v,u+1));
266  filtered_cell_x = abs(elevation_map_.at<int16_t>(v-1,u) - elevation_map_.at<int16_t>(v+1,u));
267 
268 
269  if(filtered_cell_x > filtered_cell_y)
270  filtered_cell = filtered_cell_x;
271  else
272  filtered_cell = filtered_cell_y;
273 
274  // check if cell is traversable
275  if(filtered_cell > max_delta_elevation/grid_res_z)
276  {
277  // cell is not traversable -> mark it as occupied
278  elevation_cost_map.data[cost_map_index] = OCCUPIED_CELL;
279  }
280  else
281  {
282  // cell is traversable -> mark it as free
283  elevation_cost_map.data[cost_map_index] = FREE_CELL;
284  }
285  }
286  }
287 
288  // set elevation map received flag
289  received_elevation_map = true;
290 
291  // calculate cost map
293  {
295  {
297  }
298  else
299  {
301  }
302  }
303  else
304  {
306  }
307 }
308 
309 void CostMapCalculation::callbackPointCloud(const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
310 {
311  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_sensor (new pcl::PointCloud<pcl::PointXYZ>);
312  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_base_link (new pcl::PointCloud<pcl::PointXYZ>);
313 
314  ROS_DEBUG("HectorCM: received new point cloud");
315 
316  // converting PointCloud2 msg format to pcl pointcloud format in order to read the 3d data
317  pcl::fromROSMsg(*cloud_msg, *cloud_sensor);
318 
319  // transform cloud to /map frame
320  try
321  {
322  listener.waitForTransform("base_stabilized", cloud_msg->header.frame_id,cloud_msg->header.stamp,ros::Duration(1.0));
323  pcl_ros::transformPointCloud("base_stabilized",*cloud_sensor,*cloud_base_link,listener);
324  }
325  catch (tf::TransformException ex)
326  {
327  ROS_ERROR("%s",ex.what());
328  ROS_DEBUG("HectorCM: pointcloud transform failed");
329  return;
330  }
331 
332  // compute region of intereset
333  if(!computeWindowIndices(cloud_msg->header.stamp, update_radius_world))
334  return;
335 
336  Eigen::Vector2f world_coords;
337  // define a cube with two points in space:
338  Eigen::Vector4f minPoint;
339  world_coords = world_map_transform.getC1Coords(min_index.cast<float>());
340  minPoint[0]=world_coords(0); // define minimum point x
341  minPoint[1]=world_coords(1); // define minimum point y
342  minPoint[2]=slize_min_height; // define minimum point z
343 
344  Eigen::Vector4f maxPoint;
345  world_coords = world_map_transform.getC1Coords(max_index.cast<float>());
346  maxPoint[0]=world_coords(0); // define max point x
347  maxPoint[1]=world_coords(1); // define max point y
348  maxPoint[2]=slize_max_height; // define max point z
349 
350  pcl::CropBox<pcl::PointXYZ> cropFilter;
351  cropFilter.setInputCloud (cloud_base_link);
352  cropFilter.setMin(minPoint);
353  cropFilter.setMax(maxPoint);
354  cropFilter.filter (*sliced_cloud);
355 
356  ROS_DEBUG("HectorCM: slice size: %d", (int)sliced_cloud->size());
358 
359  cloud_cost_map.data.assign(cost_map.info.width * cost_map.info.height,UNKNOWN_CELL);
360 
361  // iterate trough all points
362  for (unsigned int k = 0; k < sliced_cloud->size(); ++k)
363  {
364  const pcl::PointXYZ& pt_cloud = sliced_cloud->points[k];
365 
366  // allign grid points
367  Eigen::Vector2f index_world(pt_cloud.x, pt_cloud.y);
368  Eigen::Vector2f index_map (world_map_transform.getC2Coords(index_world));
369 
370  cloud_cost_map.data[MAP_IDX(cost_map.info.width, (int)round(index_map(0)), (int)round(index_map(1)))] = OCCUPIED_CELL;
371  }
372 
373  // set point cloud received flag
374  received_point_cloud = true;
375 
376  // calculate cost map
378  {
380  {
382  }
383  else
384  {
386  }
387  }
388 }
389 
390 void CostMapCalculation::callbackGridMap(const nav_msgs::OccupancyGridConstPtr& grid_map_msg)
391 {
392  ROS_DEBUG("HectorCM: received new grid map");
393 
394  // check header
395  if((int)(1000*grid_map_msg->info.resolution) != (int)(1000*cost_map.info.resolution) && // Magic number 1000 -> min grid size should not be less than 1mm
396  grid_map_msg->info.height != cost_map.info.height &&
397  grid_map_msg->info.width != cost_map.info.width)
398  {
399  ROS_ERROR("HectorCM: grid map resolution and or size incorrect!");
400  return;
401  }
402 
403  grid_map_msg_ = grid_map_msg;
404 
405  // copy grid_map_msg to local variable
406  grid_map_ = cv::Mat(grid_map_msg_->info.height, grid_map_msg_->info.width, CV_8S, const_cast<int8_t*>(&grid_map_msg_->data[0]), (size_t)grid_map_msg_->info.width);
407 
408  // set grid map received flag
409  received_grid_map = true;
410 
411  // compute region of intereset
412  if(!computeWindowIndices(grid_map_msg->header.stamp, update_radius_world))
413  return;
414 
415  // calculate cost map
417  {
419  {
421  }
422  else
423  {
425  }
426  }
427  else
428  {
430  {
432  }
433  else
434  {
436  }
437  }
438 }
439 
441 {
442  switch(map_level)
443  {
444  case USE_GRID_MAP_ONLY:
445  {
446  // cost map based on grid map only
447 
448  ROS_DEBUG("HectorCM: compute costmap based on grid map");
449 
450  // loop through each element
451  for (int v = min_index(1); v < max_index(1); ++v)
452  {
453  for (int u = min_index(0); u < max_index(0); ++u)
454  {
455  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
456 
457  // check if cell is known
458  if((char)grid_map_.data[index] != UNKNOWN_CELL)
459  {
460  if(grid_map_.data[index] == OCCUPIED_CELL)
461  {
462  // cell is occupied
463  cost_map.data[index] = OCCUPIED_CELL;
464  }
465  else
466  {
467  // cell is not occupied
468  cost_map.data[index] = FREE_CELL;
469  }
470  }
471  }
472  }
473 
474  break;
475  }
477  {
478  // cost map based on elevation map only
479 
480  ROS_DEBUG("HectorCM: compute costmap based on elevation map");
481 
482 
483  // loop through each element
484  for (int v = min_index(1); v < max_index(1); ++v)
485  {
486  for (int u = min_index(0); u < max_index(0); ++u)
487  {
488  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
489 
490  // check if cell is known
491  if(elevation_cost_map.data[index] != UNKNOWN_CELL)
492  {
493  if(elevation_cost_map.data[index] == OCCUPIED_CELL)
494  {
495  // cell is occupied
496  cost_map.data[index] = OCCUPIED_CELL;
497  }
498  else
499  {
500  // cell is not occupied
501  cost_map.data[index] = FREE_CELL;
502  }
503  }
504  }
505  }
506 
507  break;
508  }
510  {
511  // cost map based on elevation and grid map
512 
513  ROS_DEBUG("HectorCM: compute costmap based on grid and elevation map");
514 
515  int checksum_grid_map;
516 
517  // loop through each element
518  for (int v = min_index(1); v < max_index(1); ++v)
519  {
520  for (int u = min_index(0); u < max_index(0); ++u)
521  {
522  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
523 
524  // check if cell is known
525  if(grid_map_.at<int8_t>(v,u) != UNKNOWN_CELL)
526  {
527  if(grid_map_.at<int8_t>(v,u) == OCCUPIED_CELL || elevation_cost_map.data[index] == OCCUPIED_CELL)
528  {
529  checksum_grid_map = 0;
530 
531  checksum_grid_map += grid_map_.at<int8_t>(v-1, u);
532  checksum_grid_map += grid_map_.at<int8_t>(v+1, u);
533  checksum_grid_map += grid_map_.at<int8_t>(v, u-1);
534  checksum_grid_map += grid_map_.at<int8_t>(v, u+1);
535  checksum_grid_map += grid_map_.at<int8_t>(v+1, u+1);
536  checksum_grid_map += grid_map_.at<int8_t>(v-1, u-1);
537  checksum_grid_map += grid_map_.at<int8_t>(v+1, u-1);
538  checksum_grid_map += grid_map_.at<int8_t>(v-1, u+1);
539 
541  {
542  if(checksum_grid_map <= max_clear_size*OCCUPIED_CELL)
543  {
544  // cell is free
545  cost_map.data[index] = FREE_CELL;
546  }
547  else
548  {
549  // cell is occupied
550  cost_map.data[index] = OCCUPIED_CELL;
551  }
552  }
553  else
554  {
555  // cell is occupied
556  cost_map.data[index] = OCCUPIED_CELL;
557  }
558  }
559  else
560  {
561  cost_map.data[index] = FREE_CELL;
562  }
563  }
564  }
565  }
566  break;
567  }
569  {
570  // cost map based on cloud map and grid map
571 
572  ROS_DEBUG("HectorCM: compute costmap based on grid and cloud map");
573 
574  // loop through each element
575  for (int v = min_index(1); v < max_index(1); ++v)
576  {
577  for (int u = min_index(0); u < max_index(0); ++u)
578  {
579  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
580 
581  // check if cell is known
582  if(grid_map_.at<int8_t>(v,u) != UNKNOWN_CELL)
583  {
584  if(grid_map_.at<int8_t>(v,u) == OCCUPIED_CELL || cloud_cost_map.data[index] == OCCUPIED_CELL)
585  {
586  // cell is occupied
587  cost_map.data[index] = OCCUPIED_CELL;
588  }
589  else
590  {
591  cost_map.data[index] = FREE_CELL;
592  }
593  }
594  }
595  }
596  break;
597  }
598 
600  {
601  // cost map based on elevation, cloud and grid map
602 
603  ROS_DEBUG("HectorCM: compute costmap based on grid, cloud and elevation map");
604 
605  int checksum_grid_map;
606 
607  // loop through each element
608  for (int v = min_index(1); v < max_index(1); ++v)
609  {
610  for (int u = min_index(0); u < max_index(0); ++u)
611  {
612  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
613 
614  // check if cell is known
615  if(grid_map_.at<int8_t>(v,u) != UNKNOWN_CELL)
616  {
617  if(grid_map_.at<int8_t>(v,u) == OCCUPIED_CELL || elevation_cost_map.data[index] == OCCUPIED_CELL)
618  {
619  checksum_grid_map = 0;
620 
621  checksum_grid_map += grid_map_.at<int8_t>(v-1, u);
622  checksum_grid_map += grid_map_.at<int8_t>(v+1, u);
623  checksum_grid_map += grid_map_.at<int8_t>(v, u-1);
624  checksum_grid_map += grid_map_.at<int8_t>(v, u+1);
625  checksum_grid_map += grid_map_.at<int8_t>(v+1, u+1);
626  checksum_grid_map += grid_map_.at<int8_t>(v-1, u-1);
627  checksum_grid_map += grid_map_.at<int8_t>(v+1, u-1);
628  checksum_grid_map += grid_map_.at<int8_t>(v-1, u+1);
629 
631  {
632  if(checksum_grid_map <= max_clear_size*OCCUPIED_CELL)
633  {
634  // cell is free
635  cost_map.data[index] = FREE_CELL;
636  }
637  else
638  {
639  // cell is occupied
640  cost_map.data[index] = OCCUPIED_CELL;
641  }
642  }
643  else
644  {
645  // cell is occupied
646  cost_map.data[index] = OCCUPIED_CELL;
647  }
648  }
649  else
650  {
651  if(cloud_cost_map.data[index] == OCCUPIED_CELL)
652  {
653  // cell is occupied
654  cost_map.data[index] = OCCUPIED_CELL;
655  }
656  else
657  {
658  // cell is free
659  cost_map.data[index] = FREE_CELL;
660  }
661 
662  }
663  }
664  }
665  }
666  break;
667  }
668  }
669 
670  ROS_DEBUG("HectorCM: computed a new costmap");
671 
672  return true;
673 }
674 
676 {
677  if (!map_level)
678  {
679  ROS_WARN("Invalid map selection was given to cost map calculation!");
680  return false;
681  }
682 
683  if (map_level & GRID_MAP) ROS_DEBUG("HectorCM: compute costmap based on grid map");
684  if (map_level & ELEVATION_MAP) ROS_DEBUG("HectorCM: compute costmap based on elevation map");
685  if (map_level & CLOUD_MAP) ROS_DEBUG("HectorCM: compute costmap based on cloud map");
686 
687  // loop through each element
688  for (int v = min_index(1); v < max_index(1); ++v)
689  {
690  for (int u = min_index(0); u < max_index(0); ++u)
691  {
692  unsigned int index = MAP_IDX(cost_map.info.width, u, v);
693  int checksum_grid_map = 0;
694 
695  cost_map.data[index] = UNKNOWN_CELL;
696 
697  // grid map
698  if (map_level & GRID_MAP)
699  {
700  switch (grid_map_.data[index])
701  {
702  case OCCUPIED_CELL:
703  if (map_level & ELEVATION_MAP && allow_elevation_map_to_clear_occupied_cells)
704  {
705  checksum_grid_map += grid_map_.at<int8_t>(v-1, u );
706  checksum_grid_map += grid_map_.at<int8_t>(v+1, u );
707  checksum_grid_map += grid_map_.at<int8_t>(v, u-1);
708  checksum_grid_map += grid_map_.at<int8_t>(v, u+1);
709  checksum_grid_map += grid_map_.at<int8_t>(v+1, u+1);
710  checksum_grid_map += grid_map_.at<int8_t>(v-1, u-1);
711  checksum_grid_map += grid_map_.at<int8_t>(v+1, u-1);
712  checksum_grid_map += grid_map_.at<int8_t>(v-1, u+1);
713  }
714 
715  cost_map.data[index] = OCCUPIED_CELL;
716  break;
717  case FREE_CELL: cost_map.data[index] = FREE_CELL; break;
718  }
719  }
720 
721  // point cloud
722  if (map_level & CLOUD_MAP)
723  {
724  if (cost_map.data[index] != OCCUPIED_CELL)
725  {
726  switch (cloud_cost_map.data[index])
727  {
728  case OCCUPIED_CELL: cost_map.data[index] = OCCUPIED_CELL; break;
729  case FREE_CELL: cost_map.data[index] = FREE_CELL; break;
730  }
731  }
732  }
733 
734  // elevation map
735  if (map_level & ELEVATION_MAP)
736  {
738  {
739  switch (elevation_cost_map.data[index])
740  {
741  case OCCUPIED_CELL: cost_map.data[index] = OCCUPIED_CELL; break;
742  case FREE_CELL: cost_map.data[index] = FREE_CELL; break;
743  }
744  }
745  }
746  }
747  }
748 
749  ROS_DEBUG("HectorCM: computed a new costmap");
750 
751  return true;
752 }
753 
755 {
756  int update_radius_map;
757  Eigen::Vector2f index_world, index_map;
758 
759  // window update region
760  // only update cells within the max a curtain radius of current robot position
761  tf::StampedTransform transform;
762 
763  // get local map transform
764  try
765  {
768  }
769  catch (tf::TransformException ex)
770  {
771  ROS_ERROR("%s",ex.what());
772  return false;
773  }
774 
775  index_world(0) = transform.getOrigin().x();
776  index_world(1) = transform.getOrigin().y();
777  index_map = world_map_transform.getC2Coords(index_world);
778  update_radius_map = floor(((double)update_radius/(double)cost_map.info.resolution));
779 
780 
781  // compute window min/max index
782  if(index_map(1) < update_radius_map)
783  min_index(1) = 0;
784  else
785  min_index(1) = index_map(1) - update_radius_map;
786 
787  if(index_map(1) + update_radius_map > cost_map.info.height)
788  max_index(1) = cost_map.info.height;
789  else
790  max_index(1) = index_map(1) + update_radius_map;
791 
792  if(index_map(0) < update_radius_map)
793  min_index(0) = 0;
794  else
795  min_index(0) = index_map(0) - update_radius_map;
796 
797  if(index_map(0) + update_radius_map > cost_map.info.width)
798  max_index(0) = cost_map.info.width;
799  else
800  max_index(0) = index_map(0) + update_radius_map;
801 
802  return true;
803 }
804 
HectorMapTools::CoordinateTransformer< float > world_map_transform
#define USE_GRID_AND_ELEVATION_MAP
#define FREE_CELL
void publish(const boost::shared_ptr< M > &message) const
void callbackPointCloud(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
callbackOctoMap get called if a new octo map is available
#define CLOUD_MAP
std::string map_frame_id
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
~CostMapCalculation()
Default deconstructor.
ros::Subscriber sub_point_cloud
void sysMessageCallback(const std_msgs::String &string)
sysMessageCallback This function listen to system messages
bool calculateCostMap(char map_level)
This function fuses the elevation and grid map und calculates the 2d cost map.
std::string point_cloud_topic
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
CostMapCalculation()
Default constructor.
#define GRID_MAP
void callbackGridMap(const nav_msgs::OccupancyGridConstPtr &grid_map_msg)
callbackGridMap get called if a new 2D grid map is available
std::string grid_map_topic
#define ROS_WARN(...)
ros::Publisher pub_cloud_slice
ROSCPP_DECL void spin(Spinner &spinner)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Subscriber sub_elevation_map
std::string local_transform_frame_id
bool computeWindowIndices(ros::Time time, double update_radius)
Computes the indices for the bounding box thats get updated.
ros::Subscriber sub_grid_map
#define USE_GRID_MAP_ONLY
bool calculateCostMap_old(char map_level)
This function fuses the elevation and grid map und calculates the 2d cost map.
tf::TransformListener listener
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool allow_elevation_map_to_clear_occupied_cells
Eigen::Vector2i min_index
TFSIMD_FORCE_INLINE const tfScalar & y() const
void callbackElevationMap(const hector_elevation_msgs::ElevationGridConstPtr &elevation_map_msg)
callbackElevationMap get called if a new elevation map is available
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
#define UNKNOWN_CELL
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void dynRecParamCallback(hector_costmap::CostMapCalculationConfig &config, uint32_t level)
dynRecParamCallback This function get called if new parameters has been set with the dynamic reconfig...
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
nav_msgs::OccupancyGrid elevation_cost_map
ros::NodeHandle pnHandle
#define USE_GRID_AND_CLOUD_MAP
ros::Subscriber sub_sysMessage
std::string cost_map_topic
pcl::PointCloud< pcl::PointXYZ >::Ptr sliced_cloud
#define ELEVATION_MAP
ros::Publisher pub_cost_map
nav_msgs::OccupancyGrid cost_map
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void timerCallback(const ros::TimerEvent &event)
timerCallback publishes periodically a new 2D cost map
std::string elevation_map_topic
void updateMapParamsCallback(const nav_msgs::MapMetaData &map_meta_data)
updateMapParamsCallback updates the map meta information if someone has changed it ...
dynamic_reconfigure::Server< hector_costmap::CostMapCalculationConfig > dyn_rec_server_
static Time now()
Eigen::Vector2i max_index
nav_msgs::OccupancyGridConstPtr grid_map_msg_
#define USE_ELEVATION_MAP_ONLY
nav_msgs::OccupancyGrid cloud_cost_map
#define OCCUPIED_CELL
#define USE_GRID_AND_ELEVATION_MAP_AND_CLOUD_MAP
double initial_free_cells_radius
std::string sys_msg_topic
#define MAP_IDX(sx, i, j)
ros::NodeHandle nHandle
#define ROS_ERROR(...)
ros::Subscriber sub_map_info
#define ROS_DEBUG(...)


hector_costmap
Author(s):
autogenerated on Mon Jun 10 2019 13:34:32