-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
static_layer.cpp
510 lines (444 loc) · 15.8 KB
/
static_layer.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
/*********************************************************************
*
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, 2013, Willow Garage, Inc.
* Copyright (c) 2015, Fetch Robotics, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#include "nav2_costmap_2d/static_layer.hpp"
#include <algorithm>
#include <string>
#include "pluginlib/class_list_macros.hpp"
#include "tf2/convert.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_util/validate_messages.hpp"
PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)
using nav2_costmap_2d::NO_INFORMATION;
using nav2_costmap_2d::LETHAL_OBSTACLE;
using nav2_costmap_2d::FREE_SPACE;
using rcl_interfaces::msg::ParameterType;
namespace nav2_costmap_2d
{
StaticLayer::StaticLayer()
: map_buffer_(nullptr)
{
}
StaticLayer::~StaticLayer()
{
}
void
StaticLayer::onInitialize()
{
global_frame_ = layered_costmap_->getGlobalFrameID();
getParameters();
rclcpp::QoS map_qos(10); // initialize to default
if (map_subscribe_transient_local_) {
map_qos.transient_local();
map_qos.reliable();
map_qos.keep_last(1);
}
RCLCPP_INFO(
logger_,
"Subscribing to the map topic (%s) with %s durability",
map_topic_.c_str(),
map_subscribe_transient_local_ ? "transient local" : "volatile");
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
map_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
map_topic_, map_qos,
std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1));
if (subscribe_to_updates_) {
RCLCPP_INFO(logger_, "Subscribing to updates");
map_update_sub_ = node->create_subscription<map_msgs::msg::OccupancyGridUpdate>(
map_topic_ + "_updates",
rclcpp::SystemDefaultsQoS(),
std::bind(&StaticLayer::incomingUpdate, this, std::placeholders::_1));
}
}
void
StaticLayer::activate()
{
}
void
StaticLayer::deactivate()
{
auto node = node_.lock();
if (dyn_params_handler_ && node) {
node->remove_on_set_parameters_callback(dyn_params_handler_.get());
}
dyn_params_handler_.reset();
}
void
StaticLayer::reset()
{
has_updated_data_ = true;
current_ = false;
}
void
StaticLayer::getParameters()
{
int temp_lethal_threshold = 0;
double temp_tf_tol = 0.0;
declareParameter("enabled", rclcpp::ParameterValue(true));
declareParameter("subscribe_to_updates", rclcpp::ParameterValue(false));
declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true));
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
declareParameter("map_topic", rclcpp::ParameterValue("map"));
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
node->get_parameter(name_ + "." + "enabled", enabled_);
node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
node->get_parameter(name_ + "." + "map_topic", map_topic_);
map_topic_ = joinWithParentNamespace(map_topic_);
node->get_parameter(
name_ + "." + "map_subscribe_transient_local",
map_subscribe_transient_local_);
node->get_parameter("track_unknown_space", track_unknown_space_);
node->get_parameter("use_maximum", use_maximum_);
node->get_parameter("lethal_cost_threshold", temp_lethal_threshold);
node->get_parameter("unknown_cost_value", unknown_cost_value_);
node->get_parameter("trinary_costmap", trinary_costmap_);
node->get_parameter("transform_tolerance", temp_tf_tol);
// Enforce bounds
lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
map_received_ = false;
map_received_in_update_bounds_ = false;
transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&StaticLayer::dynamicParametersCallback,
this, std::placeholders::_1));
}
void
StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
{
RCLCPP_DEBUG(logger_, "StaticLayer: Process map");
unsigned int size_x = new_map.info.width;
unsigned int size_y = new_map.info.height;
RCLCPP_DEBUG(
logger_,
"StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
new_map.info.resolution);
// resize costmap if size, resolution or origin do not match
Costmap2D * master = layered_costmap_->getCostmap();
if (!layered_costmap_->isRolling() && (master->getSizeInCellsX() != size_x ||
master->getSizeInCellsY() != size_y ||
master->getResolution() != new_map.info.resolution ||
master->getOriginX() != new_map.info.origin.position.x ||
master->getOriginY() != new_map.info.origin.position.y ||
!layered_costmap_->isSizeLocked()))
{
// Update the size of the layered costmap (and all layers, including this one)
RCLCPP_INFO(
logger_,
"StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
new_map.info.resolution);
layered_costmap_->resizeMap(
size_x, size_y, new_map.info.resolution,
new_map.info.origin.position.x,
new_map.info.origin.position.y,
true);
} else if (size_x_ != size_x || size_y_ != size_y || // NOLINT
resolution_ != new_map.info.resolution ||
origin_x_ != new_map.info.origin.position.x ||
origin_y_ != new_map.info.origin.position.y)
{
// only update the size of the costmap stored locally in this layer
RCLCPP_INFO(
logger_,
"StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
new_map.info.resolution);
resizeMap(
size_x, size_y, new_map.info.resolution,
new_map.info.origin.position.x, new_map.info.origin.position.y);
}
unsigned int index = 0;
// we have a new map, update full size of map
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
// initialize the costmap with static data
for (unsigned int i = 0; i < size_y; ++i) {
for (unsigned int j = 0; j < size_x; ++j) {
unsigned char value = new_map.data[index];
costmap_[index] = interpretValue(value);
++index;
}
}
map_frame_ = new_map.header.frame_id;
x_ = y_ = 0;
width_ = size_x_;
height_ = size_y_;
has_updated_data_ = true;
current_ = true;
}
void
StaticLayer::matchSize()
{
// If we are using rolling costmap, the static map size is
// unrelated to the size of the layered costmap
if (!layered_costmap_->isRolling()) {
Costmap2D * master = layered_costmap_->getCostmap();
resizeMap(
master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
master->getOriginX(), master->getOriginY());
}
}
unsigned char
StaticLayer::interpretValue(unsigned char value)
{
// check if the static value is above the unknown or lethal thresholds
if (track_unknown_space_ && value == unknown_cost_value_) {
return NO_INFORMATION;
} else if (!track_unknown_space_ && value == unknown_cost_value_) {
return FREE_SPACE;
} else if (value >= lethal_threshold_) {
return LETHAL_OBSTACLE;
} else if (trinary_costmap_) {
return FREE_SPACE;
}
double scale = static_cast<double>(value) / lethal_threshold_;
return scale * LETHAL_OBSTACLE;
}
void
StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
{
if (!nav2_util::validateMsg(*new_map)) {
RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting.");
return;
}
if (!map_received_) {
processMap(*new_map);
map_received_ = true;
return;
}
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
map_buffer_ = new_map;
}
void
StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
if (update->y < static_cast<int32_t>(y_) ||
y_ + height_ < update->y + update->height ||
update->x < static_cast<int32_t>(x_) ||
x_ + width_ < update->x + update->width)
{
RCLCPP_WARN(
logger_,
"StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
"Static layer origin: %d, %d bounds: %d X %d\n"
"Update origin: %d, %d bounds: %d X %d",
x_, y_, width_, height_, update->x, update->y, update->width,
update->height);
return;
}
if (update->header.frame_id != map_frame_) {
RCLCPP_WARN(
logger_,
"StaticLayer: Map update ignored. Current map is in frame %s "
"but update was in frame %s",
map_frame_.c_str(), update->header.frame_id.c_str());
return;
}
unsigned int di = 0;
for (unsigned int y = 0; y < update->height; y++) {
unsigned int index_base = (update->y + y) * size_x_;
for (unsigned int x = 0; x < update->width; x++) {
unsigned int index = index_base + x + update->x;
costmap_[index] = interpretValue(update->data[di++]);
}
}
has_updated_data_ = true;
}
void
StaticLayer::updateBounds(
double robot_x, double robot_y, double robot_yaw, double * min_x,
double * min_y,
double * max_x,
double * max_y)
{
if (!map_received_) {
map_received_in_update_bounds_ = false;
return;
}
map_received_in_update_bounds_ = true;
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
// If there is a new available map, load it.
if (map_buffer_) {
processMap(*map_buffer_);
map_buffer_ = nullptr;
}
if (!layered_costmap_->isRolling() ) {
if (!(has_updated_data_ || has_extra_bounds_)) {
return;
}
}
useExtraBounds(min_x, min_y, max_x, max_y);
double wx, wy;
mapToWorld(x_, y_, wx, wy);
*min_x = std::min(wx, *min_x);
*min_y = std::min(wy, *min_y);
mapToWorld(x_ + width_, y_ + height_, wx, wy);
*max_x = std::max(wx, *max_x);
*max_y = std::max(wy, *max_y);
has_updated_data_ = false;
updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
}
void
StaticLayer::updateFootprint(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y,
double * max_x,
double * max_y)
{
if (!footprint_clearing_enabled_) {return;}
transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
}
}
void
StaticLayer::updateCosts(
nav2_costmap_2d::Costmap2D & master_grid,
int min_i, int min_j, int max_i, int max_j)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
if (!enabled_) {
return;
}
if (!map_received_in_update_bounds_) {
static int count = 0;
// throttle warning down to only 1/10 message rate
if (++count == 10) {
RCLCPP_WARN(logger_, "Can't update static costmap layer, no map received");
count = 0;
}
return;
}
if (footprint_clearing_enabled_) {
setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
}
if (!layered_costmap_->isRolling()) {
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
if (!use_maximum_) {
updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
} else {
updateWithMax(master_grid, min_i, min_j, max_i, max_j);
}
} else {
// If rolling window, the master_grid is unlikely to have same coordinates as this layer
unsigned int mx, my;
double wx, wy;
// Might even be in a different frame
geometry_msgs::msg::TransformStamped transform;
try {
transform = tf_->lookupTransform(
map_frame_, global_frame_, tf2::TimePointZero,
transform_tolerance_);
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(logger_, "StaticLayer: %s", ex.what());
return;
}
// Copy map data given proper transformations
tf2::Transform tf2_transform;
tf2::fromMsg(transform.transform, tf2_transform);
for (int i = min_i; i < max_i; ++i) {
for (int j = min_j; j < max_j; ++j) {
// Convert master_grid coordinates (i,j) into global_frame_(wx,wy) coordinates
layered_costmap_->getCostmap()->mapToWorld(i, j, wx, wy);
// Transform from global_frame_ to map_frame_
tf2::Vector3 p(wx, wy, 0);
p = tf2_transform * p;
// Set master_grid with cell from map
if (worldToMap(p.x(), p.y(), mx, my)) {
if (!use_maximum_) {
master_grid.setCost(i, j, getCost(mx, my));
} else {
master_grid.setCost(i, j, std::max(getCost(mx, my), master_grid.getCost(i, j)));
}
}
}
}
}
current_ = true;
}
/**
* @brief Callback executed when a parameter change is detected
* @param event ParameterEvent message
*/
rcl_interfaces::msg::SetParametersResult
StaticLayer::dynamicParametersCallback(
std::vector<rclcpp::Parameter> parameters)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name == name_ + "." + "map_subscribe_transient_local" ||
param_name == name_ + "." + "map_topic" ||
param_name == name_ + "." + "subscribe_to_updates")
{
RCLCPP_WARN(
logger_, "%s is not a dynamic parameter "
"cannot be changed while running. Rejecting parameter update.", param_name.c_str());
} else if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == name_ + "." + "transform_tolerance") {
transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
}
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
enabled_ = parameter.as_bool();
x_ = y_ = 0;
width_ = size_x_;
height_ = size_y_;
has_updated_data_ = true;
current_ = false;
}
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == name_ + "." + "footprint_clearing_enabled") {
footprint_clearing_enabled_ = parameter.as_bool();
}
}
}
result.successful = true;
return result;
}
} // namespace nav2_costmap_2d