40 #include "nav2_costmap_2d/static_layer.hpp"
45 #include "pluginlib/class_list_macros.hpp"
46 #include "tf2/convert.hpp"
47 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
48 #include "nav2_util/validate_messages.hpp"
54 using nav2_costmap_2d::NO_INFORMATION;
55 using nav2_costmap_2d::LETHAL_OBSTACLE;
56 using nav2_costmap_2d::FREE_SPACE;
57 using rcl_interfaces::msg::ParameterType;
63 : map_buffer_(nullptr)
78 rclcpp::QoS map_qos(10);
79 if (map_subscribe_transient_local_) {
80 map_qos.transient_local();
87 "Subscribing to the map topic (%s) with %s durability",
89 map_subscribe_transient_local_ ?
"transient local" :
"volatile");
91 auto node = node_.lock();
93 throw std::runtime_error{
"Failed to lock node"};
96 map_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
100 if (subscribe_to_updates_) {
101 RCLCPP_INFO(logger_,
"Subscribing to updates");
102 map_update_sub_ = node->create_subscription<map_msgs::msg::OccupancyGridUpdate>(
103 map_topic_ +
"_updates",
104 rclcpp::SystemDefaultsQoS(),
117 auto node = node_.lock();
118 if (dyn_params_handler_ && node) {
119 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
121 dyn_params_handler_.reset();
134 int temp_lethal_threshold = 0;
135 double temp_tf_tol = 0.0;
139 declareParameter(
"map_subscribe_transient_local", rclcpp::ParameterValue(
true));
142 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
false));
143 declareParameter(
"restore_cleared_footprint", rclcpp::ParameterValue(
true));
145 auto node = node_.lock();
147 throw std::runtime_error{
"Failed to lock node"};
150 node->get_parameter(name_ +
"." +
"enabled", enabled_);
151 node->get_parameter(name_ +
"." +
"subscribe_to_updates", subscribe_to_updates_);
152 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
153 node->get_parameter(name_ +
"." +
"restore_cleared_footprint", restore_cleared_footprint_);
154 node->get_parameter(name_ +
"." +
"map_topic", map_topic_);
157 name_ +
"." +
"map_subscribe_transient_local",
158 map_subscribe_transient_local_);
159 node->get_parameter(
"track_unknown_space", track_unknown_space_);
160 node->get_parameter(
"use_maximum", use_maximum_);
161 node->get_parameter(
"lethal_cost_threshold", temp_lethal_threshold);
162 node->get_parameter(
"unknown_cost_value", unknown_cost_value_);
163 node->get_parameter(
"trinary_costmap", trinary_costmap_);
164 node->get_parameter(
"transform_tolerance", temp_tf_tol);
167 lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
168 map_received_ =
false;
169 map_received_in_update_bounds_ =
false;
171 transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
174 dyn_params_handler_ = node->add_on_set_parameters_callback(
177 this, std::placeholders::_1));
183 RCLCPP_DEBUG(logger_,
"StaticLayer: Process map");
185 unsigned int size_x = new_map.info.width;
186 unsigned int size_y = new_map.info.height;
190 "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
191 new_map.info.resolution);
205 "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
206 new_map.info.resolution);
208 size_x, size_y, new_map.info.resolution,
209 new_map.info.origin.position.x,
210 new_map.info.origin.position.y,
212 }
else if (size_x_ != size_x || size_y_ != size_y ||
213 !
isEqual(resolution_, new_map.info.resolution, EPSILON) ||
214 !
isEqual(origin_x_, new_map.info.origin.position.x, EPSILON) ||
215 !
isEqual(origin_y_, new_map.info.origin.position.y, EPSILON))
220 "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
221 new_map.info.resolution);
223 size_x, size_y, new_map.info.resolution,
224 new_map.info.origin.position.x, new_map.info.origin.position.y);
227 unsigned int index = 0;
230 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
233 for (
unsigned int i = 0; i < size_y; ++i) {
234 for (
unsigned int j = 0; j < size_x; ++j) {
235 unsigned char value = new_map.data[index];
241 map_frame_ = new_map.header.frame_id;
268 if (track_unknown_space_ && value == unknown_cost_value_) {
269 return NO_INFORMATION;
270 }
else if (!track_unknown_space_ && value == unknown_cost_value_) {
272 }
else if (value >= lethal_threshold_) {
273 return LETHAL_OBSTACLE;
274 }
else if (trinary_costmap_) {
278 double scale =
static_cast<double>(value) / lethal_threshold_;
279 return scale * LETHAL_OBSTACLE;
285 if (!nav2_util::validateMsg(*new_map)) {
286 RCLCPP_ERROR(logger_,
"Received map message is malformed. Rejecting.");
289 if (!map_received_) {
291 map_received_ =
true;
294 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
295 map_buffer_ = new_map;
301 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
302 if (update->y <
static_cast<int32_t
>(y_) ||
303 y_ + height_ < update->y + update->height ||
304 update->x <
static_cast<int32_t
>(x_) ||
305 x_ + width_ < update->x + update->width)
309 "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
310 "Static layer origin: %d, %d bounds: %d X %d\n"
311 "Update origin: %d, %d bounds: %d X %d",
312 x_, y_, width_, height_, update->x, update->y, update->width,
317 if (update->header.frame_id != map_frame_) {
320 "StaticLayer: Map update ignored. Current map is in frame %s "
321 "but update was in frame %s",
322 map_frame_.c_str(), update->header.frame_id.c_str());
327 for (
unsigned int y = 0; y < update->height; y++) {
328 unsigned int index_base = (update->y + y) * size_x_;
329 for (
unsigned int x = 0; x < update->width; x++) {
330 unsigned int index = index_base + x + update->x;
341 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
346 if (!map_received_) {
347 map_received_in_update_bounds_ =
false;
350 map_received_in_update_bounds_ =
true;
352 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
357 map_buffer_ =
nullptr;
366 useExtraBounds(min_x, min_y, max_x, max_y);
371 *min_x = std::min(wx, *min_x);
372 *min_y = std::min(wy, *min_y);
374 mapToWorld(x_ + width_, y_ + height_, wx, wy);
375 *max_x = std::max(wx, *max_x);
376 *max_y = std::max(wy, *max_y);
380 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
385 double robot_x,
double robot_y,
double robot_yaw,
386 double * min_x,
double * min_y,
390 if (!footprint_clearing_enabled_) {
return;}
394 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
395 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
402 int min_i,
int min_j,
int max_i,
int max_j)
404 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
408 if (!map_received_in_update_bounds_) {
409 static int count = 0;
412 RCLCPP_WARN(logger_,
"Can't update static costmap layer, no map received");
418 std::vector<MapLocation> map_region_to_restore;
419 if (footprint_clearing_enabled_) {
420 map_region_to_restore.reserve(100);
428 updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
430 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
437 geometry_msgs::msg::TransformStamped transform;
439 transform = tf_->lookupTransform(
441 transform_tolerance_);
442 }
catch (tf2::TransformException & ex) {
443 RCLCPP_ERROR(logger_,
"StaticLayer: %s", ex.what());
447 tf2::Transform tf2_transform;
448 tf2::fromMsg(transform.transform, tf2_transform);
450 for (
int i = min_i; i < max_i; ++i) {
451 for (
int j = min_j; j < max_j; ++j) {
455 tf2::Vector3 p(wx, wy, 0);
456 p = tf2_transform * p;
469 if (footprint_clearing_enabled_ && restore_cleared_footprint_) {
485 return std::abs(a - b) < epsilon;
492 rcl_interfaces::msg::SetParametersResult
494 std::vector<rclcpp::Parameter> parameters)
496 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
497 rcl_interfaces::msg::SetParametersResult result;
499 for (
auto parameter : parameters) {
500 const auto & param_type = parameter.get_type();
501 const auto & param_name = parameter.get_name();
502 if (param_name.find(name_ +
".") != 0) {
506 if (param_name == name_ +
"." +
"map_subscribe_transient_local" ||
507 param_name == name_ +
"." +
"map_topic" ||
508 param_name == name_ +
"." +
"subscribe_to_updates")
511 logger_,
"%s is not a dynamic parameter "
512 "cannot be changed while running. Rejecting parameter update.", param_name.c_str());
513 }
else if (param_type == ParameterType::PARAMETER_DOUBLE) {
514 if (param_name == name_ +
"." +
"transform_tolerance") {
515 transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
517 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
518 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
519 enabled_ = parameter.as_bool();
526 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
527 footprint_clearing_enabled_ = parameter.as_bool();
528 }
else if (param_name == name_ +
"." +
"restore_cleared_footprint") {
529 if (footprint_clearing_enabled_) {
530 restore_cleared_footprint_ = parameter.as_bool();
532 RCLCPP_WARN(logger_,
"restore_cleared_footprint cannot be used "
533 "when footprint_clearing_enabled is False. Rejecting parameter update.");
538 result.successful =
true;
A 2D costmap provides a mapping between points in the world and their associated "costs".
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
double getResolution() const
Accessor for the resolution of the costmap.
void setMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region, unsigned char new_cost_value)
Sets the given map region to desired value.
void restoreMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region)
Restores the corresponding map region using given map region.
bool getMapRegionOccupiedByPolygon(const std::vector< geometry_msgs::msg::Point > &polygon, std::vector< MapLocation > &polygon_map_region)
Gets the map region occupied by polygon.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
Abstract class for layered costmap plugin implementations.
std::string joinWithParentNamespace(const std::string &topic)
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
bool isRolling()
If this costmap is rolling or not.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Resize the map to a new size, resolution, or origin.
bool isSizeLocked()
Get if the size of the costmap is locked.
Takes in a map generated from SLAM to add costs to costmap.
void getParameters()
Get parameters of layer.
virtual ~StaticLayer()
Static Layer destructor.
virtual void deactivate()
Deactivate this layer.
bool has_updated_data_
frame that map is located in
unsigned char interpretValue(unsigned char value)
Interpret the value in the static map given on the topic to convert into costs for the costmap to uti...
StaticLayer()
Static Layer constructor.
virtual void matchSize()
Match the size of the master costmap.
virtual void onInitialize()
Initialization process of layer on startup.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void activate()
Activate this layer.
void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
Callback to update the costmap's map from the map_server (or SLAM) with an update in a particular are...
bool isEqual(double a, double b, double epsilon)
Check if two double values are equal within a given epsilon.
void incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
Callback to update the costmap's map from the map_server.
std::string global_frame_
The global frame for the costmap.
void processMap(const nav_msgs::msg::OccupancyGrid &new_map)
Process a new map coming from a topic.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual void reset()
Reset this costmap.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)