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"
52 using nav2_costmap_2d::NO_INFORMATION;
53 using nav2_costmap_2d::LETHAL_OBSTACLE;
54 using nav2_costmap_2d::FREE_SPACE;
55 using rcl_interfaces::msg::ParameterType;
61 : map_buffer_(nullptr)
76 rclcpp::QoS map_qos(10);
77 if (map_subscribe_transient_local_) {
78 map_qos.transient_local();
85 "Subscribing to the map topic (%s) with %s durability",
87 map_subscribe_transient_local_ ?
"transient local" :
"volatile");
89 auto node = node_.lock();
91 throw std::runtime_error{
"Failed to lock node"};
94 map_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
98 if (subscribe_to_updates_) {
99 RCLCPP_INFO(logger_,
"Subscribing to updates");
100 map_update_sub_ = node->create_subscription<map_msgs::msg::OccupancyGridUpdate>(
101 map_topic_ +
"_updates",
102 rclcpp::SystemDefaultsQoS(),
115 auto node = node_.lock();
116 if (dyn_params_handler_ && node) {
117 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
119 dyn_params_handler_.reset();
132 int temp_lethal_threshold = 0;
133 double temp_tf_tol = 0.0;
137 declareParameter(
"map_subscribe_transient_local", rclcpp::ParameterValue(
true));
140 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
false));
141 declareParameter(
"restore_cleared_footprint", rclcpp::ParameterValue(
true));
143 auto node = node_.lock();
145 throw std::runtime_error{
"Failed to lock node"};
148 node->get_parameter(name_ +
"." +
"enabled", enabled_);
149 node->get_parameter(name_ +
"." +
"subscribe_to_updates", subscribe_to_updates_);
150 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
151 node->get_parameter(name_ +
"." +
"restore_cleared_footprint", restore_cleared_footprint_);
152 node->get_parameter(name_ +
"." +
"map_topic", map_topic_);
155 name_ +
"." +
"map_subscribe_transient_local",
156 map_subscribe_transient_local_);
157 node->get_parameter(
"track_unknown_space", track_unknown_space_);
158 node->get_parameter(
"use_maximum", use_maximum_);
159 node->get_parameter(
"lethal_cost_threshold", temp_lethal_threshold);
160 node->get_parameter(
"unknown_cost_value", unknown_cost_value_);
161 node->get_parameter(
"trinary_costmap", trinary_costmap_);
162 node->get_parameter(
"transform_tolerance", temp_tf_tol);
165 lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
166 map_received_ =
false;
167 map_received_in_update_bounds_ =
false;
169 transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
172 dyn_params_handler_ = node->add_on_set_parameters_callback(
175 this, std::placeholders::_1));
181 RCLCPP_DEBUG(logger_,
"StaticLayer: Process map");
183 unsigned int size_x = new_map.info.width;
184 unsigned int size_y = new_map.info.height;
188 "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
189 new_map.info.resolution);
196 master->
getOriginX() != new_map.info.origin.position.x ||
197 master->
getOriginY() != new_map.info.origin.position.y ||
203 "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
204 new_map.info.resolution);
206 size_x, size_y, new_map.info.resolution,
207 new_map.info.origin.position.x,
208 new_map.info.origin.position.y,
210 }
else if (size_x_ != size_x || size_y_ != size_y ||
211 resolution_ != new_map.info.resolution ||
212 origin_x_ != new_map.info.origin.position.x ||
213 origin_y_ != new_map.info.origin.position.y)
218 "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
219 new_map.info.resolution);
221 size_x, size_y, new_map.info.resolution,
222 new_map.info.origin.position.x, new_map.info.origin.position.y);
225 unsigned int index = 0;
228 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
231 for (
unsigned int i = 0; i < size_y; ++i) {
232 for (
unsigned int j = 0; j < size_x; ++j) {
233 unsigned char value = new_map.data[index];
239 map_frame_ = new_map.header.frame_id;
266 if (track_unknown_space_ && value == unknown_cost_value_) {
267 return NO_INFORMATION;
268 }
else if (!track_unknown_space_ && value == unknown_cost_value_) {
270 }
else if (value >= lethal_threshold_) {
271 return LETHAL_OBSTACLE;
272 }
else if (trinary_costmap_) {
276 double scale =
static_cast<double>(value) / lethal_threshold_;
277 return scale * LETHAL_OBSTACLE;
283 if (!nav2_util::validateMsg(*new_map)) {
284 RCLCPP_ERROR(logger_,
"Received map message is malformed. Rejecting.");
287 if (!map_received_) {
289 map_received_ =
true;
292 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
293 map_buffer_ = new_map;
299 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
300 if (update->y <
static_cast<int32_t
>(y_) ||
301 y_ + height_ < update->y + update->height ||
302 update->x <
static_cast<int32_t
>(x_) ||
303 x_ + width_ < update->x + update->width)
307 "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
308 "Static layer origin: %d, %d bounds: %d X %d\n"
309 "Update origin: %d, %d bounds: %d X %d",
310 x_, y_, width_, height_, update->x, update->y, update->width,
315 if (update->header.frame_id != map_frame_) {
318 "StaticLayer: Map update ignored. Current map is in frame %s "
319 "but update was in frame %s",
320 map_frame_.c_str(), update->header.frame_id.c_str());
325 for (
unsigned int y = 0; y < update->height; y++) {
326 unsigned int index_base = (update->y + y) * size_x_;
327 for (
unsigned int x = 0; x < update->width; x++) {
328 unsigned int index = index_base + x + update->x;
339 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
344 if (!map_received_) {
345 map_received_in_update_bounds_ =
false;
348 map_received_in_update_bounds_ =
true;
350 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
355 map_buffer_ =
nullptr;
364 useExtraBounds(min_x, min_y, max_x, max_y);
369 *min_x = std::min(wx, *min_x);
370 *min_y = std::min(wy, *min_y);
372 mapToWorld(x_ + width_, y_ + height_, wx, wy);
373 *max_x = std::max(wx, *max_x);
374 *max_y = std::max(wy, *max_y);
378 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
383 double robot_x,
double robot_y,
double robot_yaw,
384 double * min_x,
double * min_y,
388 if (!footprint_clearing_enabled_) {
return;}
392 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
393 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
400 int min_i,
int min_j,
int max_i,
int max_j)
402 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
406 if (!map_received_in_update_bounds_) {
407 static int count = 0;
410 RCLCPP_WARN(logger_,
"Can't update static costmap layer, no map received");
416 std::vector<MapLocation> map_region_to_restore;
417 if (footprint_clearing_enabled_) {
418 map_region_to_restore.reserve(100);
426 updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
428 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
435 geometry_msgs::msg::TransformStamped transform;
437 transform = tf_->lookupTransform(
439 transform_tolerance_);
440 }
catch (tf2::TransformException & ex) {
441 RCLCPP_ERROR(logger_,
"StaticLayer: %s", ex.what());
445 tf2::Transform tf2_transform;
446 tf2::fromMsg(transform.transform, tf2_transform);
448 for (
int i = min_i; i < max_i; ++i) {
449 for (
int j = min_j; j < max_j; ++j) {
453 tf2::Vector3 p(wx, wy, 0);
454 p = tf2_transform * p;
467 if (footprint_clearing_enabled_ && restore_cleared_footprint_) {
478 rcl_interfaces::msg::SetParametersResult
480 std::vector<rclcpp::Parameter> parameters)
482 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
483 rcl_interfaces::msg::SetParametersResult result;
485 for (
auto parameter : parameters) {
486 const auto & param_type = parameter.get_type();
487 const auto & param_name = parameter.get_name();
488 if (param_name.find(name_ +
".") != 0) {
492 if (param_name == name_ +
"." +
"map_subscribe_transient_local" ||
493 param_name == name_ +
"." +
"map_topic" ||
494 param_name == name_ +
"." +
"subscribe_to_updates")
497 logger_,
"%s is not a dynamic parameter "
498 "cannot be changed while running. Rejecting parameter update.", param_name.c_str());
499 }
else if (param_type == ParameterType::PARAMETER_DOUBLE) {
500 if (param_name == name_ +
"." +
"transform_tolerance") {
501 transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
503 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
504 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
505 enabled_ = parameter.as_bool();
512 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
513 footprint_clearing_enabled_ = parameter.as_bool();
514 }
else if (param_name == name_ +
"." +
"restore_cleared_footprint") {
515 if (footprint_clearing_enabled_) {
516 restore_cleared_footprint_ = parameter.as_bool();
518 RCLCPP_WARN(logger_,
"restore_cleared_footprint cannot be used "
519 "when footprint_clearing_enabled is False. Rejecting parameter update.");
524 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...
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)