voxel_layer.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449
  1. /*********************************************************************
  2. *
  3. * Software License Agreement (BSD License)
  4. *
  5. * Copyright (c) 2008, 2013, Willow Garage, Inc.
  6. * All rights reserved.
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * * Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * * Redistributions in binary form must reproduce the above
  15. * copyright notice, this list of conditions and the following
  16. * disclaimer in the documentation and/or other materials provided
  17. * with the distribution.
  18. * * Neither the name of Willow Garage, Inc. nor the names of its
  19. * contributors may be used to endorse or promote products derived
  20. * from this software without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  29. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  30. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. * Author: Eitan Marder-Eppstein
  36. * David V. Lu!!
  37. *********************************************************************/
  38. #include <costmap_2d/voxel_layer.h>
  39. #include <pluginlib/class_list_macros.hpp>
  40. #include <sensor_msgs/point_cloud2_iterator.h>
  41. #define VOXEL_BITS 16
  42. PLUGINLIB_EXPORT_CLASS(costmap_2d::VoxelLayer, costmap_2d::Layer)
  43. using costmap_2d::NO_INFORMATION;
  44. using costmap_2d::LETHAL_OBSTACLE;
  45. using costmap_2d::FREE_SPACE;
  46. using costmap_2d::ObservationBuffer;
  47. using costmap_2d::Observation;
  48. namespace costmap_2d
  49. {
  50. void VoxelLayer::onInitialize()
  51. {
  52. ObstacleLayer::onInitialize();
  53. ros::NodeHandle private_nh("~/" + name_);
  54. private_nh.param("publish_voxel_map", publish_voxel_, false);
  55. if (publish_voxel_)
  56. voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > ("voxel_grid", 1);
  57. clearing_endpoints_pub_ = private_nh.advertise<sensor_msgs::PointCloud>("clearing_endpoints", 1);
  58. }
  59. void VoxelLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
  60. {
  61. voxel_dsrv_ = new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
  62. dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb =
  63. [this](auto& config, auto level){ reconfigureCB(config, level); };
  64. voxel_dsrv_->setCallback(cb);
  65. }
  66. VoxelLayer::~VoxelLayer()
  67. {
  68. if (voxel_dsrv_)
  69. delete voxel_dsrv_;
  70. }
  71. void VoxelLayer::reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
  72. {
  73. enabled_ = config.enabled;
  74. footprint_clearing_enabled_ = config.footprint_clearing_enabled;
  75. max_obstacle_height_ = config.max_obstacle_height;
  76. size_z_ = config.z_voxels;
  77. origin_z_ = config.origin_z;
  78. z_resolution_ = config.z_resolution;
  79. unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
  80. mark_threshold_ = config.mark_threshold;
  81. combination_method_ = config.combination_method;
  82. matchSize();
  83. }
  84. void VoxelLayer::matchSize()
  85. {
  86. ObstacleLayer::matchSize();
  87. voxel_grid_.resize(size_x_, size_y_, size_z_);
  88. ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
  89. }
  90. void VoxelLayer::reset()
  91. {
  92. deactivate();
  93. resetMaps();
  94. voxel_grid_.reset();
  95. activate();
  96. }
  97. void VoxelLayer::resetMaps()
  98. {
  99. Costmap2D::resetMaps();
  100. voxel_grid_.reset();
  101. }
  102. void VoxelLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
  103. double* min_y, double* max_x, double* max_y)
  104. {
  105. if (rolling_window_)
  106. updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
  107. useExtraBounds(min_x, min_y, max_x, max_y);
  108. bool current = true;
  109. std::vector<Observation> observations, clearing_observations;
  110. // get the marking observations
  111. current = getMarkingObservations(observations) && current;
  112. // get the clearing observations
  113. current = getClearingObservations(clearing_observations) && current;
  114. // update the global current status
  115. current_ = current;
  116. // raytrace freespace
  117. for (unsigned int i = 0; i < clearing_observations.size(); ++i)
  118. {
  119. raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
  120. }
  121. // place the new obstacles into a priority queue... each with a priority of zero to begin with
  122. for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
  123. {
  124. const Observation& obs = *it;
  125. const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
  126. double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
  127. sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
  128. sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
  129. sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
  130. for (unsigned int i = 0; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
  131. {
  132. // if the obstacle is too high or too far away from the robot we won't add it
  133. if (*iter_z > max_obstacle_height_)
  134. continue;
  135. // compute the squared distance from the hitpoint to the pointcloud's origin
  136. double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x)
  137. + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y)
  138. + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
  139. // if the point is far enough away... we won't consider it
  140. if (sq_dist >= sq_obstacle_range)
  141. continue;
  142. // now we need to compute the map coordinates for the observation
  143. unsigned int mx, my, mz;
  144. if (*iter_z < origin_z_)
  145. {
  146. if (!worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz))
  147. continue;
  148. }
  149. else if (!worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz))
  150. {
  151. continue;
  152. }
  153. // mark the cell in the voxel grid and check if we should also mark it in the costmap
  154. if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
  155. {
  156. unsigned int index = getIndex(mx, my);
  157. costmap_[index] = LETHAL_OBSTACLE;
  158. touch(double(*iter_x), double(*iter_y), min_x, min_y, max_x, max_y);
  159. }
  160. }
  161. }
  162. if (publish_voxel_)
  163. {
  164. costmap_2d::VoxelGrid grid_msg;
  165. unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
  166. grid_msg.size_x = voxel_grid_.sizeX();
  167. grid_msg.size_y = voxel_grid_.sizeY();
  168. grid_msg.size_z = voxel_grid_.sizeZ();
  169. grid_msg.data.resize(size);
  170. memcpy(&grid_msg.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
  171. grid_msg.origin.x = origin_x_;
  172. grid_msg.origin.y = origin_y_;
  173. grid_msg.origin.z = origin_z_;
  174. grid_msg.resolutions.x = resolution_;
  175. grid_msg.resolutions.y = resolution_;
  176. grid_msg.resolutions.z = z_resolution_;
  177. grid_msg.header.frame_id = global_frame_;
  178. grid_msg.header.stamp = ros::Time::now();
  179. voxel_pub_.publish(grid_msg);
  180. }
  181. updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
  182. }
  183. void VoxelLayer::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
  184. {
  185. // get the cell coordinates of the center point of the window
  186. unsigned int mx, my;
  187. if (!worldToMap(wx, wy, mx, my))
  188. return;
  189. // compute the bounds of the window
  190. double start_x = wx - w_size_x / 2;
  191. double start_y = wy - w_size_y / 2;
  192. double end_x = start_x + w_size_x;
  193. double end_y = start_y + w_size_y;
  194. // scale the window based on the bounds of the costmap
  195. start_x = std::max(origin_x_, start_x);
  196. start_y = std::max(origin_y_, start_y);
  197. end_x = std::min(origin_x_ + getSizeInMetersX(), end_x);
  198. end_y = std::min(origin_y_ + getSizeInMetersY(), end_y);
  199. // get the map coordinates of the bounds of the window
  200. unsigned int map_sx, map_sy, map_ex, map_ey;
  201. // check for legality just in case
  202. if (!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
  203. return;
  204. // we know that we want to clear all non-lethal obstacles in this window to get it ready for inflation
  205. unsigned int index = getIndex(map_sx, map_sy);
  206. unsigned char* current = &costmap_[index];
  207. for (unsigned int j = map_sy; j <= map_ey; ++j)
  208. {
  209. for (unsigned int i = map_sx; i <= map_ex; ++i)
  210. {
  211. // if the cell is a lethal obstacle... we'll keep it and queue it, otherwise... we'll clear it
  212. if (*current != LETHAL_OBSTACLE)
  213. {
  214. if (clear_no_info || *current != NO_INFORMATION)
  215. {
  216. *current = FREE_SPACE;
  217. voxel_grid_.clearVoxelColumn(index);
  218. }
  219. }
  220. current++;
  221. index++;
  222. }
  223. current += size_x_ - (map_ex - map_sx) - 1;
  224. index += size_x_ - (map_ex - map_sx) - 1;
  225. }
  226. }
  227. void VoxelLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
  228. double* max_x, double* max_y)
  229. {
  230. size_t clearing_observation_cloud_size = clearing_observation.cloud_->height * clearing_observation.cloud_->width;
  231. if (clearing_observation_cloud_size == 0)
  232. return;
  233. double sensor_x, sensor_y, sensor_z;
  234. double ox = clearing_observation.origin_.x;
  235. double oy = clearing_observation.origin_.y;
  236. double oz = clearing_observation.origin_.z;
  237. if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z))
  238. {
  239. ROS_WARN_THROTTLE(
  240. 1.0,
  241. "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
  242. ox, oy, oz);
  243. return;
  244. }
  245. bool publish_clearing_points = (clearing_endpoints_pub_.getNumSubscribers() > 0);
  246. if (publish_clearing_points)
  247. {
  248. clearing_endpoints_.points.clear();
  249. clearing_endpoints_.points.reserve(clearing_observation_cloud_size);
  250. }
  251. // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
  252. double map_end_x = origin_x_ + getSizeInMetersX();
  253. double map_end_y = origin_y_ + getSizeInMetersY();
  254. sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_), "x");
  255. sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_), "y");
  256. sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_), "z");
  257. for (;iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
  258. {
  259. double wpx = *iter_x;
  260. double wpy = *iter_y;
  261. double wpz = *iter_z;
  262. double distance = dist(ox, oy, oz, wpx, wpy, wpz);
  263. double scaling_fact = 1.0;
  264. scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
  265. wpx = scaling_fact * (wpx - ox) + ox;
  266. wpy = scaling_fact * (wpy - oy) + oy;
  267. wpz = scaling_fact * (wpz - oz) + oz;
  268. double a = wpx - ox;
  269. double b = wpy - oy;
  270. double c = wpz - oz;
  271. double t = 1.0;
  272. // we can only raytrace to a maximum z height
  273. if (wpz > max_obstacle_height_)
  274. {
  275. // we know we want the vector's z value to be max_z
  276. t = std::max(0.0, std::min(t, (max_obstacle_height_ - 0.01 - oz) / c));
  277. }
  278. // and we can only raytrace down to the floor
  279. else if (wpz < origin_z_)
  280. {
  281. // we know we want the vector's z value to be 0.0
  282. t = std::min(t, (origin_z_ - oz) / c);
  283. }
  284. // the minimum value to raytrace from is the origin
  285. if (wpx < origin_x_)
  286. {
  287. t = std::min(t, (origin_x_ - ox) / a);
  288. }
  289. if (wpy < origin_y_)
  290. {
  291. t = std::min(t, (origin_y_ - oy) / b);
  292. }
  293. // the maximum value to raytrace to is the end of the map
  294. if (wpx > map_end_x)
  295. {
  296. t = std::min(t, (map_end_x - ox) / a);
  297. }
  298. if (wpy > map_end_y)
  299. {
  300. t = std::min(t, (map_end_y - oy) / b);
  301. }
  302. wpx = ox + a * t;
  303. wpy = oy + b * t;
  304. wpz = oz + c * t;
  305. double point_x, point_y, point_z;
  306. if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z))
  307. {
  308. unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
  309. // voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
  310. voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_,
  311. unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
  312. cell_raytrace_range);
  313. updateRaytraceBounds(ox, oy, wpx, wpy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
  314. if (publish_clearing_points)
  315. {
  316. geometry_msgs::Point32 point;
  317. point.x = wpx;
  318. point.y = wpy;
  319. point.z = wpz;
  320. clearing_endpoints_.points.push_back(point);
  321. }
  322. }
  323. }
  324. if (publish_clearing_points)
  325. {
  326. clearing_endpoints_.header.frame_id = global_frame_;
  327. clearing_endpoints_.header.stamp = clearing_observation.cloud_->header.stamp;
  328. clearing_endpoints_.header.seq = clearing_observation.cloud_->header.seq;
  329. clearing_endpoints_pub_.publish(clearing_endpoints_);
  330. }
  331. }
  332. void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
  333. {
  334. // project the new origin into the grid
  335. int cell_ox, cell_oy;
  336. cell_ox = int((new_origin_x - origin_x_) / resolution_);
  337. cell_oy = int((new_origin_y - origin_y_) / resolution_);
  338. // compute the associated world coordinates for the origin cell
  339. // beacuase we want to keep things grid-aligned
  340. double new_grid_ox, new_grid_oy;
  341. new_grid_ox = origin_x_ + cell_ox * resolution_;
  342. new_grid_oy = origin_y_ + cell_oy * resolution_;
  343. // To save casting from unsigned int to int a bunch of times
  344. int size_x = size_x_;
  345. int size_y = size_y_;
  346. // we need to compute the overlap of the new and existing windows
  347. int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
  348. lower_left_x = std::min(std::max(cell_ox, 0), size_x);
  349. lower_left_y = std::min(std::max(cell_oy, 0), size_y);
  350. upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
  351. upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
  352. unsigned int cell_size_x = upper_right_x - lower_left_x;
  353. unsigned int cell_size_y = upper_right_y - lower_left_y;
  354. // we need a map to store the obstacles in the window temporarily
  355. unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
  356. unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
  357. unsigned int* voxel_map = voxel_grid_.getData();
  358. // copy the local window in the costmap to the local map
  359. copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
  360. copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
  361. cell_size_y);
  362. // we'll reset our maps to unknown space if appropriate
  363. resetMaps();
  364. // update the origin with the appropriate world coordinates
  365. origin_x_ = new_grid_ox;
  366. origin_y_ = new_grid_oy;
  367. // compute the starting cell location for copying data back in
  368. int start_x = lower_left_x - cell_ox;
  369. int start_y = lower_left_y - cell_oy;
  370. // now we want to copy the overlapping information back into the map, but in its new location
  371. copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
  372. copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
  373. // make sure to clean up
  374. delete[] local_map;
  375. delete[] local_voxel_map;
  376. }
  377. } // namespace costmap_2d