static_layer.cpp
Go to the documentation of this file.
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  *********************************************************************/
42 #include <tf2/convert.h>
44 
46 
50 
51 namespace costmap_2d
52 {
53 
54 StaticLayer::StaticLayer() : dsrv_(NULL) {}
55 
57 {
58  if (dsrv_)
59  delete dsrv_;
60 }
61 
63 {
64  ros::NodeHandle nh("~/" + name_), g_nh;
65  current_ = true;
66 
68 
69  std::string map_topic;
70  nh.param("map_topic", map_topic, std::string("map"));
71  nh.param("first_map_only", first_map_only_, false);
72  nh.param("subscribe_to_updates", subscribe_to_updates_, false);
73 
74  nh.param("track_unknown_space", track_unknown_space_, true);
75  nh.param("use_maximum", use_maximum_, false);
76 
77  int temp_lethal_threshold, temp_unknown_cost_value;
78  nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
79  nh.param("unknown_cost_value", temp_unknown_cost_value, int(-1));
80  nh.param("trinary_costmap", trinary_costmap_, true);
81 
82  lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
83  unknown_cost_value_ = temp_unknown_cost_value;
84 
85  // Only resubscribe if topic has changed
86  if (map_sub_.getTopic() != ros::names::resolve(map_topic))
87  {
88  // we'll subscribe to the latched topic that the map server uses
89  ROS_INFO("Requesting the map...");
90  map_sub_ = g_nh.subscribe(map_topic, 1, &StaticLayer::incomingMap, this);
91  map_received_ = false;
92  has_updated_data_ = false;
93 
94  ros::Rate r(10);
95  while (!map_received_ && g_nh.ok())
96  {
97  ros::spinOnce();
98  r.sleep();
99  }
100 
101  ROS_INFO("Received a %d X %d map at %f m/pix", getSizeInCellsX(), getSizeInCellsY(), getResolution());
102 
104  {
105  ROS_INFO("Subscribing to updates");
106  map_update_sub_ = g_nh.subscribe(map_topic + "_updates", 10, &StaticLayer::incomingUpdate, this);
107 
108  }
109  }
110  else
111  {
112  has_updated_data_ = true;
113  }
114 
115  if (dsrv_)
116  {
117  delete dsrv_;
118  }
119 
120  dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
121  dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb =
122  [this](auto& config, auto level){ reconfigureCB(config, level); };
123  dsrv_->setCallback(cb);
124 }
125 
126 void StaticLayer::reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
127 {
128  if (config.enabled != enabled_)
129  {
130  enabled_ = config.enabled;
131  has_updated_data_ = true;
132  x_ = y_ = 0;
133  width_ = size_x_;
134  height_ = size_y_;
135  }
136 }
137 
139 {
140  // If we are using rolling costmap, the static map size is
141  // unrelated to the size of the layered costmap
142  if (!layered_costmap_->isRolling())
143  {
145  resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
146  master->getOriginX(), master->getOriginY());
147  }
148 }
149 
150 unsigned char StaticLayer::interpretValue(unsigned char value)
151 {
152  // check if the static value is above the unknown or lethal thresholds
154  return NO_INFORMATION;
155  else if (!track_unknown_space_ && value == unknown_cost_value_)
156  return FREE_SPACE;
157  else if (value >= lethal_threshold_)
158  return LETHAL_OBSTACLE;
159  else if (trinary_costmap_)
160  return FREE_SPACE;
161 
162  double scale = (double) value / lethal_threshold_;
163  return scale * LETHAL_OBSTACLE;
164 }
165 
166 void StaticLayer::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map)
167 {
168  unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
169 
170  ROS_DEBUG("Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
171 
172  // resize costmap if size, resolution or origin do not match
174  if (!layered_costmap_->isRolling() &&
175  (master->getSizeInCellsX() != size_x ||
176  master->getSizeInCellsY() != size_y ||
177  master->getResolution() != new_map->info.resolution ||
178  master->getOriginX() != new_map->info.origin.position.x ||
179  master->getOriginY() != new_map->info.origin.position.y))
180  {
181  // Update the size of the layered costmap (and all layers, including this one)
182  ROS_INFO("Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
183  layered_costmap_->resizeMap(size_x, size_y, new_map->info.resolution, new_map->info.origin.position.x,
184  new_map->info.origin.position.y,
185  true /* set size_locked to true, prevents reconfigureCb from overriding map size*/);
186  }
187  else if (size_x_ != size_x || size_y_ != size_y ||
188  resolution_ != new_map->info.resolution ||
189  origin_x_ != new_map->info.origin.position.x ||
190  origin_y_ != new_map->info.origin.position.y)
191  {
192  // only update the size of the costmap stored locally in this layer
193  ROS_INFO("Resizing static layer to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
194  resizeMap(size_x, size_y, new_map->info.resolution,
195  new_map->info.origin.position.x, new_map->info.origin.position.y);
196  }
197 
198  unsigned int index = 0;
199 
200  // initialize the costmap with static data
201  for (unsigned int i = 0; i < size_y; ++i)
202  {
203  for (unsigned int j = 0; j < size_x; ++j)
204  {
205  unsigned char value = new_map->data[index];
206  costmap_[index] = interpretValue(value);
207  ++index;
208  }
209  }
210  map_frame_ = new_map->header.frame_id;
211 
212  // we have a new map, update full size of map
213  x_ = y_ = 0;
214  width_ = size_x_;
215  height_ = size_y_;
216  map_received_ = true;
217  has_updated_data_ = true;
218 
219  // shutdown the map subscrber if firt_map_only_ flag is on
220  if (first_map_only_)
221  {
222  ROS_INFO("Shutting down the map subscriber. first_map_only flag is on");
223  map_sub_.shutdown();
224  }
225 }
226 
227 void StaticLayer::incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
228 {
229  unsigned int di = 0;
230  for (unsigned int y = 0; y < update->height ; y++)
231  {
232  unsigned int index_base = (update->y + y) * size_x_;
233  for (unsigned int x = 0; x < update->width ; x++)
234  {
235  unsigned int index = index_base + x + update->x;
236  costmap_[index] = interpretValue(update->data[di++]);
237  }
238  }
239  x_ = update->x;
240  y_ = update->y;
241  width_ = update->width;
242  height_ = update->height;
243  has_updated_data_ = true;
244 }
245 
247 {
248  onInitialize();
249 }
250 
252 {
253  map_sub_.shutdown();
256 }
257 
259 {
260  if (first_map_only_)
261  {
262  has_updated_data_ = true;
263  }
264  else
265  {
266  onInitialize();
267  }
268 }
269 
270 void StaticLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
271  double* max_x, double* max_y)
272 {
273 
274  if( !layered_costmap_->isRolling() ){
276  return;
277  }
278 
279  useExtraBounds(min_x, min_y, max_x, max_y);
280 
281  double wx, wy;
282 
283  mapToWorld(x_, y_, wx, wy);
284  *min_x = std::min(wx, *min_x);
285  *min_y = std::min(wy, *min_y);
286 
287  mapToWorld(x_ + width_, y_ + height_, wx, wy);
288  *max_x = std::max(wx, *max_x);
289  *max_y = std::max(wy, *max_y);
290 
291  has_updated_data_ = false;
292 }
293 
294 void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
295 {
296  if (!map_received_)
297  return;
298 
299  if (!layered_costmap_->isRolling())
300  {
301  // if not rolling, the layered costmap (master_grid) has same coordinates as this layer
302  if (!use_maximum_)
303  updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
304  else
305  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
306  }
307  else
308  {
309  // If rolling window, the master_grid is unlikely to have same coordinates as this layer
310  unsigned int mx, my;
311  double wx, wy;
312  // Might even be in a different frame
313  geometry_msgs::TransformStamped transform;
314  try
315  {
317  }
318  catch (tf2::TransformException ex)
319  {
320  ROS_ERROR("%s", ex.what());
321  return;
322  }
323  // Copy map data given proper transformations
324  tf2::Transform tf2_transform;
325  tf2::convert(transform.transform, tf2_transform);
326  for (unsigned int i = min_i; i < max_i; ++i)
327  {
328  for (unsigned int j = min_j; j < max_j; ++j)
329  {
330  // Convert master_grid coordinates (i,j) into global_frame_(wx,wy) coordinates
331  layered_costmap_->getCostmap()->mapToWorld(i, j, wx, wy);
332  // Transform from global_frame_ to map_frame_
333  tf2::Vector3 p(wx, wy, 0);
334  p = tf2_transform*p;
335  // Set master_grid with cell from map
336  if (worldToMap(p.x(), p.y(), mx, my))
337  {
338  if (!use_maximum_)
339  master_grid.setCost(i, j, getCost(mx, my));
340  else
341  master_grid.setCost(i, j, std::max(getCost(mx, my), master_grid.getCost(i, j)));
342  }
343  }
344  }
345  }
346 }
347 
348 } // namespace costmap_2d
costmap_2d::StaticLayer::lethal_threshold_
unsigned char lethal_threshold_
Definition: static_layer.h:166
costmap_2d::StaticLayer::map_received_
bool map_received_
Definition: static_layer.h:157
tf2::convert
void convert(const A &a, B &b)
costmap_2d::StaticLayer::reconfigureCB
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
Definition: static_layer.cpp:126
costmap_2d::StaticLayer::use_maximum_
bool use_maximum_
Definition: static_layer.h:161
costmap_2d::CostmapLayer::updateWithMax
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:63
costmap_2d::Layer::tf_
tf2_ros::Buffer * tf_
Definition: layer.h:178
costmap_2d::StaticLayer::updateBounds
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
Definition: static_layer.cpp:270
costmap_2d::StaticLayer::map_sub_
ros::Subscriber map_sub_
Definition: static_layer.h:164
costmap_2d::Layer::enabled_
bool enabled_
Definition: layer.h:176
costmap_2d::StaticLayer::subscribe_to_updates_
bool subscribe_to_updates_
frame that map is located in
Definition: static_layer.h:156
costmap_2d::LayeredCostmap::isRolling
bool isRolling()
Definition: layered_costmap.h:133
costmap_2d::Costmap2D::worldToMap
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:208
costmap_2d::StaticLayer::width_
unsigned int width_
Definition: static_layer.h:159
costmap_2d::StaticLayer::has_updated_data_
bool has_updated_data_
Definition: static_layer.h:158
costmap_2d::StaticLayer::activate
virtual void activate()
Restart publishers if they've been stopped.
Definition: static_layer.cpp:246
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
Definition: cost_values.h:77
ros::Subscriber::getTopic
std::string getTopic() const
costmap_2d::Costmap2D::origin_x_
double origin_x_
Definition: costmap_2d.h:460
costmap_2d::LayeredCostmap::resizeMap
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Definition: layered_costmap.cpp:82
ros::spinOnce
ROSCPP_DECL void spinOnce()
costmap_2d::StaticLayer::interpretValue
unsigned char interpretValue(unsigned char value)
Definition: static_layer.cpp:150
ros::Subscriber::shutdown
void shutdown()
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
costmap_2d::Costmap2D::mapToWorld
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:202
costmap_2d::StaticLayer::map_update_sub_
ros::Subscriber map_update_sub_
Definition: static_layer.h:164
costmap_2d::Costmap2D::getOriginX
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:450
costmap_2d::Layer::name_
std::string name_
Definition: layer.h:177
costmap_2d::Layer::current_
bool current_
Definition: layer.h:175
costmap_2d::Layer::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: layer.h:174
costmap_2d::StaticLayer::onInitialize
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: static_layer.cpp:62
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
costmap_2d::StaticLayer::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: static_layer.h:154
costmap_2d::StaticLayer::track_unknown_space_
bool track_unknown_space_
Definition: static_layer.h:160
costmap_2d::StaticLayer::map_frame_
std::string map_frame_
Definition: static_layer.h:155
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
ROS_DEBUG
#define ROS_DEBUG(...)
costmap_2d::Costmap2D::resizeMap
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Definition: costmap_2d.cpp:72
costmap_2d::Costmap2D::setCost
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:197
costmap_2d::CostmapLayer::has_extra_bounds_
bool has_extra_bounds_
Definition: costmap_layer.h:216
tf2::Transform
costmap_2d::Costmap2D::size_y_
unsigned int size_y_
Definition: costmap_2d.h:458
costmap_2d::StaticLayer::matchSize
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: static_layer.cpp:138
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:435
costmap_2d::StaticLayer::deactivate
virtual void deactivate()
Stop publishers.
Definition: static_layer.cpp:251
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:78
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
costmap_math.h
costmap_2d::StaticLayer::trinary_costmap_
bool trinary_costmap_
Definition: static_layer.h:163
costmap_2d::StaticLayer::y_
unsigned int y_
Definition: static_layer.h:159
ros::Rate::sleep
bool sleep()
costmap_2d::StaticLayer
Definition: static_layer.h:89
costmap_2d::StaticLayer::x_
unsigned int x_
Definition: static_layer.h:159
costmap_2d::StaticLayer::first_map_only_
bool first_map_only_
Store the first static map and reuse it on reinitializing.
Definition: static_layer.h:162
costmap_2d::CostmapLayer::useExtraBounds
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
Definition: costmap_layer.cpp:47
costmap_2d::Costmap2D::size_x_
unsigned int size_x_
Definition: costmap_2d.h:457
costmap_2d::CostmapLayer::updateWithTrueOverwrite
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:89
ros::NodeHandle::ok
bool ok() const
costmap_2d::Costmap2D::getOriginY
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:455
ros::Time
costmap_2d::Costmap2D::resolution_
double resolution_
Definition: costmap_2d.h:459
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
costmap_2d::Costmap2D::origin_y_
double origin_y_
Definition: costmap_2d.h:461
costmap_2d::StaticLayer::reset
virtual void reset()
Definition: static_layer.cpp:258
tf2_geometry_msgs.h
costmap_2d::Costmap2D::getResolution
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:460
costmap_2d::Layer
Definition: layer.h:84
ros::Rate
costmap_2d::StaticLayer::incomingUpdate
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
Definition: static_layer.cpp:227
convert.h
costmap_2d::Costmap2D::costmap_
unsigned char * costmap_
Definition: costmap_2d.h:462
costmap_2d::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
Definition: cost_values.h:80
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:430
costmap_2d::LayeredCostmap::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
Definition: layered_costmap.h:110
static_layer.h
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
costmap_2d::StaticLayer::~StaticLayer
virtual ~StaticLayer()
Definition: static_layer.cpp:56
costmap_2d::StaticLayer::StaticLayer
StaticLayer()
Definition: static_layer.cpp:54
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:192
costmap_2d
Definition: array_parser.h:37
costmap_2d::StaticLayer::dsrv_
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
Definition: static_layer.h:168
costmap_2d::StaticLayer::updateCosts
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
Definition: static_layer.cpp:294
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
costmap_2d::StaticLayer::unknown_cost_value_
unsigned char unknown_cost_value_
Definition: static_layer.h:166
ros::NodeHandle
costmap_2d::StaticLayer::height_
unsigned int height_
Definition: static_layer.h:159
costmap_2d::StaticLayer::incomingMap
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
Definition: static_layer.cpp:166


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17