inflation_layer.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385
  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 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 <algorithm>
  39. #include <costmap_2d/inflation_layer.h>
  40. #include <costmap_2d/costmap_math.h>
  41. #include <costmap_2d/footprint.h>
  42. #include <boost/thread.hpp>
  43. #include <pluginlib/class_list_macros.hpp>
  44. PLUGINLIB_EXPORT_CLASS(costmap_2d::InflationLayer, costmap_2d::Layer)
  45. using costmap_2d::LETHAL_OBSTACLE;
  46. using costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
  47. using costmap_2d::NO_INFORMATION;
  48. namespace costmap_2d
  49. {
  50. InflationLayer::InflationLayer()
  51. : resolution_(0)
  52. , inflation_radius_(0)
  53. , inscribed_radius_(0)
  54. , weight_(0)
  55. , inflate_unknown_(false)
  56. , cell_inflation_radius_(0)
  57. , cached_cell_inflation_radius_(0)
  58. , dsrv_(NULL)
  59. , seen_(NULL)
  60. , cached_costs_(NULL)
  61. , cached_distances_(NULL)
  62. , last_min_x_(-std::numeric_limits<float>::max())
  63. , last_min_y_(-std::numeric_limits<float>::max())
  64. , last_max_x_(std::numeric_limits<float>::max())
  65. , last_max_y_(std::numeric_limits<float>::max())
  66. {
  67. inflation_access_ = new boost::recursive_mutex();
  68. }
  69. void InflationLayer::onInitialize()
  70. {
  71. {
  72. boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
  73. ros::NodeHandle nh("~/" + name_), g_nh;
  74. current_ = true;
  75. if (seen_)
  76. delete[] seen_;
  77. seen_ = NULL;
  78. seen_size_ = 0;
  79. need_reinflation_ = false;
  80. dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb =
  81. [this](auto& config, auto level){ reconfigureCB(config, level); };
  82. if (dsrv_ != NULL){
  83. dsrv_->clearCallback();
  84. dsrv_->setCallback(cb);
  85. }
  86. else
  87. {
  88. dsrv_ = new dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>(ros::NodeHandle("~/" + name_));
  89. dsrv_->setCallback(cb);
  90. }
  91. }
  92. matchSize();
  93. }
  94. void InflationLayer::reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
  95. {
  96. setInflationParameters(config.inflation_radius, config.cost_scaling_factor);
  97. if (enabled_ != config.enabled || inflate_unknown_ != config.inflate_unknown) {
  98. enabled_ = config.enabled;
  99. inflate_unknown_ = config.inflate_unknown;
  100. need_reinflation_ = true;
  101. }
  102. }
  103. void InflationLayer::matchSize()
  104. {
  105. boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
  106. costmap_2d::Costmap2D* costmap = layered_costmap_->getCostmap();
  107. resolution_ = costmap->getResolution();
  108. cell_inflation_radius_ = cellDistance(inflation_radius_);
  109. computeCaches();
  110. unsigned int size_x = costmap->getSizeInCellsX(), size_y = costmap->getSizeInCellsY();
  111. if (seen_)
  112. delete[] seen_;
  113. seen_size_ = size_x * size_y;
  114. seen_ = new bool[seen_size_];
  115. }
  116. void InflationLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
  117. double* min_y, double* max_x, double* max_y)
  118. {
  119. if (need_reinflation_)
  120. {
  121. last_min_x_ = *min_x;
  122. last_min_y_ = *min_y;
  123. last_max_x_ = *max_x;
  124. last_max_y_ = *max_y;
  125. // For some reason when I make these -<double>::max() it does not
  126. // work with Costmap2D::worldToMapEnforceBounds(), so I'm using
  127. // -<float>::max() instead.
  128. *min_x = -std::numeric_limits<float>::max();
  129. *min_y = -std::numeric_limits<float>::max();
  130. *max_x = std::numeric_limits<float>::max();
  131. *max_y = std::numeric_limits<float>::max();
  132. need_reinflation_ = false;
  133. }
  134. else
  135. {
  136. double tmp_min_x = last_min_x_;
  137. double tmp_min_y = last_min_y_;
  138. double tmp_max_x = last_max_x_;
  139. double tmp_max_y = last_max_y_;
  140. last_min_x_ = *min_x;
  141. last_min_y_ = *min_y;
  142. last_max_x_ = *max_x;
  143. last_max_y_ = *max_y;
  144. *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
  145. *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
  146. *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
  147. *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
  148. }
  149. }
  150. void InflationLayer::onFootprintChanged()
  151. {
  152. inscribed_radius_ = layered_costmap_->getInscribedRadius();
  153. cell_inflation_radius_ = cellDistance(inflation_radius_);
  154. computeCaches();
  155. need_reinflation_ = true;
  156. ROS_DEBUG("InflationLayer::onFootprintChanged(): num footprint points: %lu,"
  157. " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
  158. layered_costmap_->getFootprint().size(), inscribed_radius_, inflation_radius_);
  159. }
  160. void InflationLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
  161. {
  162. boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
  163. if (cell_inflation_radius_ == 0)
  164. return;
  165. // make sure the inflation list is empty at the beginning of the cycle (should always be true)
  166. ROS_ASSERT_MSG(inflation_cells_.empty(), "The inflation list must be empty at the beginning of inflation");
  167. unsigned char* master_array = master_grid.getCharMap();
  168. unsigned int size_x = master_grid.getSizeInCellsX(), size_y = master_grid.getSizeInCellsY();
  169. if (seen_ == NULL) {
  170. ROS_WARN("InflationLayer::updateCosts(): seen_ array is NULL");
  171. seen_size_ = size_x * size_y;
  172. seen_ = new bool[seen_size_];
  173. }
  174. else if (seen_size_ != size_x * size_y)
  175. {
  176. ROS_WARN("InflationLayer::updateCosts(): seen_ array size is wrong");
  177. delete[] seen_;
  178. seen_size_ = size_x * size_y;
  179. seen_ = new bool[seen_size_];
  180. }
  181. memset(seen_, false, size_x * size_y * sizeof(bool));
  182. // We need to include in the inflation cells outside the bounding
  183. // box min_i...max_j, by the amount cell_inflation_radius_. Cells
  184. // up to that distance outside the box can still influence the costs
  185. // stored in cells inside the box.
  186. min_i -= cell_inflation_radius_;
  187. min_j -= cell_inflation_radius_;
  188. max_i += cell_inflation_radius_;
  189. max_j += cell_inflation_radius_;
  190. min_i = std::max(0, min_i);
  191. min_j = std::max(0, min_j);
  192. max_i = std::min(int(size_x), max_i);
  193. max_j = std::min(int(size_y), max_j);
  194. // Inflation list; we append cells to visit in a list associated with its distance to the nearest obstacle
  195. // We use a map<distance, list> to emulate the priority queue used before, with a notable performance boost
  196. // Start with lethal obstacles: by definition distance is 0.0
  197. std::vector<CellData>& obs_bin = inflation_cells_[0.0];
  198. for (int j = min_j; j < max_j; j++)
  199. {
  200. for (int i = min_i; i < max_i; i++)
  201. {
  202. int index = master_grid.getIndex(i, j);
  203. unsigned char cost = master_array[index];
  204. if (cost == LETHAL_OBSTACLE)
  205. {
  206. obs_bin.push_back(CellData(index, i, j, i, j));
  207. }
  208. }
  209. }
  210. // Process cells by increasing distance; new cells are appended to the corresponding distance bin, so they
  211. // can overtake previously inserted but farther away cells
  212. std::map<double, std::vector<CellData> >::iterator bin;
  213. for (bin = inflation_cells_.begin(); bin != inflation_cells_.end(); ++bin)
  214. {
  215. for (int i = 0; i < bin->second.size(); ++i)
  216. {
  217. // process all cells at distance dist_bin.first
  218. const CellData& cell = bin->second[i];
  219. unsigned int index = cell.index_;
  220. // ignore if already visited
  221. if (seen_[index])
  222. {
  223. continue;
  224. }
  225. seen_[index] = true;
  226. unsigned int mx = cell.x_;
  227. unsigned int my = cell.y_;
  228. unsigned int sx = cell.src_x_;
  229. unsigned int sy = cell.src_y_;
  230. // assign the cost associated with the distance from an obstacle to the cell
  231. unsigned char cost = costLookup(mx, my, sx, sy);
  232. unsigned char old_cost = master_array[index];
  233. if (old_cost == NO_INFORMATION && (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
  234. master_array[index] = cost;
  235. else
  236. master_array[index] = std::max(old_cost, cost);
  237. // attempt to put the neighbors of the current cell onto the inflation list
  238. if (mx > 0)
  239. enqueue(index - 1, mx - 1, my, sx, sy);
  240. if (my > 0)
  241. enqueue(index - size_x, mx, my - 1, sx, sy);
  242. if (mx < size_x - 1)
  243. enqueue(index + 1, mx + 1, my, sx, sy);
  244. if (my < size_y - 1)
  245. enqueue(index + size_x, mx, my + 1, sx, sy);
  246. }
  247. }
  248. inflation_cells_.clear();
  249. }
  250. /**
  251. * @brief Given an index of a cell in the costmap, place it into a list pending for obstacle inflation
  252. * @param grid The costmap
  253. * @param index The index of the cell
  254. * @param mx The x coordinate of the cell (can be computed from the index, but saves time to store it)
  255. * @param my The y coordinate of the cell (can be computed from the index, but saves time to store it)
  256. * @param src_x The x index of the obstacle point inflation started at
  257. * @param src_y The y index of the obstacle point inflation started at
  258. */
  259. inline void InflationLayer::enqueue(unsigned int index, unsigned int mx, unsigned int my,
  260. unsigned int src_x, unsigned int src_y)
  261. {
  262. if (!seen_[index])
  263. {
  264. // we compute our distance table one cell further than the inflation radius dictates so we can make the check below
  265. double distance = distanceLookup(mx, my, src_x, src_y);
  266. // we only want to put the cell in the list if it is within the inflation radius of the obstacle point
  267. if (distance > cell_inflation_radius_)
  268. return;
  269. // push the cell data onto the inflation list and mark
  270. inflation_cells_[distance].push_back(CellData(index, mx, my, src_x, src_y));
  271. }
  272. }
  273. void InflationLayer::computeCaches()
  274. {
  275. if (cell_inflation_radius_ == 0)
  276. return;
  277. // based on the inflation radius... compute distance and cost caches
  278. if (cell_inflation_radius_ != cached_cell_inflation_radius_)
  279. {
  280. deleteKernels();
  281. cached_costs_ = new unsigned char*[cell_inflation_radius_ + 2];
  282. cached_distances_ = new double*[cell_inflation_radius_ + 2];
  283. for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
  284. {
  285. cached_costs_[i] = new unsigned char[cell_inflation_radius_ + 2];
  286. cached_distances_[i] = new double[cell_inflation_radius_ + 2];
  287. for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
  288. {
  289. cached_distances_[i][j] = hypot(i, j);
  290. }
  291. }
  292. cached_cell_inflation_radius_ = cell_inflation_radius_;
  293. }
  294. for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
  295. {
  296. for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
  297. {
  298. cached_costs_[i][j] = computeCost(cached_distances_[i][j]);
  299. }
  300. }
  301. }
  302. void InflationLayer::deleteKernels()
  303. {
  304. if (cached_distances_ != NULL)
  305. {
  306. for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
  307. {
  308. if (cached_distances_[i])
  309. delete[] cached_distances_[i];
  310. }
  311. if (cached_distances_)
  312. delete[] cached_distances_;
  313. cached_distances_ = NULL;
  314. }
  315. if (cached_costs_ != NULL)
  316. {
  317. for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
  318. {
  319. if (cached_costs_[i])
  320. delete[] cached_costs_[i];
  321. }
  322. delete[] cached_costs_;
  323. cached_costs_ = NULL;
  324. }
  325. }
  326. void InflationLayer::setInflationParameters(double inflation_radius, double cost_scaling_factor)
  327. {
  328. if (weight_ != cost_scaling_factor || inflation_radius_ != inflation_radius)
  329. {
  330. // Lock here so that reconfiguring the inflation radius doesn't cause segfaults
  331. // when accessing the cached arrays
  332. boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
  333. inflation_radius_ = inflation_radius;
  334. cell_inflation_radius_ = cellDistance(inflation_radius_);
  335. weight_ = cost_scaling_factor;
  336. need_reinflation_ = true;
  337. computeCaches();
  338. }
  339. }
  340. } // namespace costmap_2d