static_layer.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348
  1. /*********************************************************************
  2. *
  3. * Software License Agreement (BSD License)
  4. *
  5. * Copyright (c) 2008, 2013, Willow Garage, Inc.
  6. * Copyright (c) 2015, Fetch Robotics, Inc.
  7. * All rights reserved.
  8. *
  9. * Redistribution and use in source and binary forms, with or without
  10. * modification, are permitted provided that the following conditions
  11. * are met:
  12. *
  13. * * Redistributions of source code must retain the above copyright
  14. * notice, this list of conditions and the following disclaimer.
  15. * * Redistributions in binary form must reproduce the above
  16. * copyright notice, this list of conditions and the following
  17. * disclaimer in the documentation and/or other materials provided
  18. * with the distribution.
  19. * * Neither the name of Willow Garage, Inc. nor the names of its
  20. * contributors may be used to endorse or promote products derived
  21. * from this software without specific prior written permission.
  22. *
  23. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  24. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  25. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  26. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  27. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  28. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  29. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  30. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  31. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  32. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  33. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  34. * POSSIBILITY OF SUCH DAMAGE.
  35. *
  36. * Author: Eitan Marder-Eppstein
  37. * David V. Lu!!
  38. *********************************************************************/
  39. #include <costmap_2d/static_layer.h>
  40. #include <costmap_2d/costmap_math.h>
  41. #include <pluginlib/class_list_macros.hpp>
  42. #include <tf2/convert.h>
  43. #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
  44. PLUGINLIB_EXPORT_CLASS(costmap_2d::StaticLayer, costmap_2d::Layer)
  45. using costmap_2d::NO_INFORMATION;
  46. using costmap_2d::LETHAL_OBSTACLE;
  47. using costmap_2d::FREE_SPACE;
  48. namespace costmap_2d
  49. {
  50. StaticLayer::StaticLayer() : dsrv_(NULL) {}
  51. StaticLayer::~StaticLayer()
  52. {
  53. if (dsrv_)
  54. delete dsrv_;
  55. }
  56. void StaticLayer::onInitialize()
  57. {
  58. ros::NodeHandle nh("~/" + name_), g_nh;
  59. current_ = true;
  60. global_frame_ = layered_costmap_->getGlobalFrameID();
  61. std::string map_topic;
  62. nh.param("map_topic", map_topic, std::string("map"));
  63. nh.param("first_map_only", first_map_only_, false);
  64. nh.param("subscribe_to_updates", subscribe_to_updates_, false);
  65. nh.param("track_unknown_space", track_unknown_space_, true);
  66. nh.param("use_maximum", use_maximum_, false);
  67. int temp_lethal_threshold, temp_unknown_cost_value;
  68. nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
  69. nh.param("unknown_cost_value", temp_unknown_cost_value, int(-1));
  70. nh.param("trinary_costmap", trinary_costmap_, true);
  71. lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
  72. unknown_cost_value_ = temp_unknown_cost_value;
  73. // Only resubscribe if topic has changed
  74. if (map_sub_.getTopic() != ros::names::resolve(map_topic))
  75. {
  76. // we'll subscribe to the latched topic that the map server uses
  77. ROS_INFO("Requesting the map...");
  78. map_sub_ = g_nh.subscribe(map_topic, 1, &StaticLayer::incomingMap, this);
  79. map_received_ = false;
  80. has_updated_data_ = false;
  81. ros::Rate r(10);
  82. while (!map_received_ && g_nh.ok())
  83. {
  84. ros::spinOnce();
  85. r.sleep();
  86. }
  87. ROS_INFO("Received a %d X %d map at %f m/pix", getSizeInCellsX(), getSizeInCellsY(), getResolution());
  88. if (subscribe_to_updates_)
  89. {
  90. ROS_INFO("Subscribing to updates");
  91. map_update_sub_ = g_nh.subscribe(map_topic + "_updates", 10, &StaticLayer::incomingUpdate, this);
  92. }
  93. }
  94. else
  95. {
  96. has_updated_data_ = true;
  97. }
  98. if (dsrv_)
  99. {
  100. delete dsrv_;
  101. }
  102. dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
  103. dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb =
  104. [this](auto& config, auto level){ reconfigureCB(config, level); };
  105. dsrv_->setCallback(cb);
  106. }
  107. void StaticLayer::reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
  108. {
  109. if (config.enabled != enabled_)
  110. {
  111. enabled_ = config.enabled;
  112. has_updated_data_ = true;
  113. x_ = y_ = 0;
  114. width_ = size_x_;
  115. height_ = size_y_;
  116. }
  117. }
  118. void StaticLayer::matchSize()
  119. {
  120. // If we are using rolling costmap, the static map size is
  121. // unrelated to the size of the layered costmap
  122. if (!layered_costmap_->isRolling())
  123. {
  124. Costmap2D* master = layered_costmap_->getCostmap();
  125. resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
  126. master->getOriginX(), master->getOriginY());
  127. }
  128. }
  129. unsigned char StaticLayer::interpretValue(unsigned char value)
  130. {
  131. // check if the static value is above the unknown or lethal thresholds
  132. if (track_unknown_space_ && value == unknown_cost_value_)
  133. return NO_INFORMATION;
  134. else if (!track_unknown_space_ && value == unknown_cost_value_)
  135. return FREE_SPACE;
  136. else if (value >= lethal_threshold_)
  137. return LETHAL_OBSTACLE;
  138. else if (trinary_costmap_)
  139. return FREE_SPACE;
  140. double scale = (double) value / lethal_threshold_;
  141. return scale * LETHAL_OBSTACLE;
  142. }
  143. void StaticLayer::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map)
  144. {
  145. unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
  146. ROS_DEBUG("Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
  147. // resize costmap if size, resolution or origin do not match
  148. Costmap2D* master = layered_costmap_->getCostmap();
  149. if (!layered_costmap_->isRolling() &&
  150. (master->getSizeInCellsX() != size_x ||
  151. master->getSizeInCellsY() != size_y ||
  152. master->getResolution() != new_map->info.resolution ||
  153. master->getOriginX() != new_map->info.origin.position.x ||
  154. master->getOriginY() != new_map->info.origin.position.y))
  155. {
  156. // Update the size of the layered costmap (and all layers, including this one)
  157. ROS_INFO("Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
  158. layered_costmap_->resizeMap(size_x, size_y, new_map->info.resolution, new_map->info.origin.position.x,
  159. new_map->info.origin.position.y,
  160. true /* set size_locked to true, prevents reconfigureCb from overriding map size*/);
  161. }
  162. else if (size_x_ != size_x || size_y_ != size_y ||
  163. resolution_ != new_map->info.resolution ||
  164. origin_x_ != new_map->info.origin.position.x ||
  165. origin_y_ != new_map->info.origin.position.y)
  166. {
  167. // only update the size of the costmap stored locally in this layer
  168. ROS_INFO("Resizing static layer to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
  169. resizeMap(size_x, size_y, new_map->info.resolution,
  170. new_map->info.origin.position.x, new_map->info.origin.position.y);
  171. }
  172. unsigned int index = 0;
  173. // initialize the costmap with static data
  174. for (unsigned int i = 0; i < size_y; ++i)
  175. {
  176. for (unsigned int j = 0; j < size_x; ++j)
  177. {
  178. unsigned char value = new_map->data[index];
  179. costmap_[index] = interpretValue(value);
  180. ++index;
  181. }
  182. }
  183. map_frame_ = new_map->header.frame_id;
  184. // we have a new map, update full size of map
  185. x_ = y_ = 0;
  186. width_ = size_x_;
  187. height_ = size_y_;
  188. map_received_ = true;
  189. has_updated_data_ = true;
  190. // shutdown the map subscrber if firt_map_only_ flag is on
  191. if (first_map_only_)
  192. {
  193. ROS_INFO("Shutting down the map subscriber. first_map_only flag is on");
  194. map_sub_.shutdown();
  195. }
  196. }
  197. void StaticLayer::incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
  198. {
  199. unsigned int di = 0;
  200. for (unsigned int y = 0; y < update->height ; y++)
  201. {
  202. unsigned int index_base = (update->y + y) * size_x_;
  203. for (unsigned int x = 0; x < update->width ; x++)
  204. {
  205. unsigned int index = index_base + x + update->x;
  206. costmap_[index] = interpretValue(update->data[di++]);
  207. }
  208. }
  209. x_ = update->x;
  210. y_ = update->y;
  211. width_ = update->width;
  212. height_ = update->height;
  213. has_updated_data_ = true;
  214. }
  215. void StaticLayer::activate()
  216. {
  217. onInitialize();
  218. }
  219. void StaticLayer::deactivate()
  220. {
  221. map_sub_.shutdown();
  222. if (subscribe_to_updates_)
  223. map_update_sub_.shutdown();
  224. }
  225. void StaticLayer::reset()
  226. {
  227. if (first_map_only_)
  228. {
  229. has_updated_data_ = true;
  230. }
  231. else
  232. {
  233. onInitialize();
  234. }
  235. }
  236. void StaticLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
  237. double* max_x, double* max_y)
  238. {
  239. if( !layered_costmap_->isRolling() ){
  240. if (!map_received_ || !(has_updated_data_ || has_extra_bounds_))
  241. return;
  242. }
  243. useExtraBounds(min_x, min_y, max_x, max_y);
  244. double wx, wy;
  245. mapToWorld(x_, y_, wx, wy);
  246. *min_x = std::min(wx, *min_x);
  247. *min_y = std::min(wy, *min_y);
  248. mapToWorld(x_ + width_, y_ + height_, wx, wy);
  249. *max_x = std::max(wx, *max_x);
  250. *max_y = std::max(wy, *max_y);
  251. has_updated_data_ = false;
  252. }
  253. void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
  254. {
  255. if (!map_received_)
  256. return;
  257. if (!layered_costmap_->isRolling())
  258. {
  259. // if not rolling, the layered costmap (master_grid) has same coordinates as this layer
  260. if (!use_maximum_)
  261. updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
  262. else
  263. updateWithMax(master_grid, min_i, min_j, max_i, max_j);
  264. }
  265. else
  266. {
  267. // If rolling window, the master_grid is unlikely to have same coordinates as this layer
  268. unsigned int mx, my;
  269. double wx, wy;
  270. // Might even be in a different frame
  271. geometry_msgs::TransformStamped transform;
  272. try
  273. {
  274. transform = tf_->lookupTransform(map_frame_, global_frame_, ros::Time(0));
  275. }
  276. catch (tf2::TransformException ex)
  277. {
  278. ROS_ERROR("%s", ex.what());
  279. return;
  280. }
  281. // Copy map data given proper transformations
  282. tf2::Transform tf2_transform;
  283. tf2::convert(transform.transform, tf2_transform);
  284. for (unsigned int i = min_i; i < max_i; ++i)
  285. {
  286. for (unsigned int j = min_j; j < max_j; ++j)
  287. {
  288. // Convert master_grid coordinates (i,j) into global_frame_(wx,wy) coordinates
  289. layered_costmap_->getCostmap()->mapToWorld(i, j, wx, wy);
  290. // Transform from global_frame_ to map_frame_
  291. tf2::Vector3 p(wx, wy, 0);
  292. p = tf2_transform*p;
  293. // Set master_grid with cell from map
  294. if (worldToMap(p.x(), p.y(), mx, my))
  295. {
  296. if (!use_maximum_)
  297. master_grid.setCost(i, j, getCost(mx, my));
  298. else
  299. master_grid.setCost(i, j, std::max(getCost(mx, my), master_grid.getCost(i, j)));
  300. }
  301. }
  302. }
  303. }
  304. }
  305. } // namespace costmap_2d