40 #include "nav2_costmap_2d/static_layer.hpp"
45 #include "pluginlib/class_list_macros.hpp"
46 #include "tf2/convert.h"
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));
142 auto node = node_.lock();
144 throw std::runtime_error{
"Failed to lock node"};
147 node->get_parameter(name_ +
"." +
"enabled", enabled_);
148 node->get_parameter(name_ +
"." +
"subscribe_to_updates", subscribe_to_updates_);
149 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
150 std::string private_map_topic, global_map_topic;
151 node->get_parameter(name_ +
"." +
"map_topic", private_map_topic);
152 node->get_parameter(
"map_topic", global_map_topic);
153 if (!private_map_topic.empty()) {
154 map_topic_ = private_map_topic;
156 map_topic_ = global_map_topic;
159 name_ +
"." +
"map_subscribe_transient_local",
160 map_subscribe_transient_local_);
161 node->get_parameter(
"track_unknown_space", track_unknown_space_);
162 node->get_parameter(
"use_maximum", use_maximum_);
163 node->get_parameter(
"lethal_cost_threshold", temp_lethal_threshold);
164 node->get_parameter(
"unknown_cost_value", unknown_cost_value_);
165 node->get_parameter(
"trinary_costmap", trinary_costmap_);
166 node->get_parameter(
"transform_tolerance", temp_tf_tol);
169 lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
170 map_received_ =
false;
171 map_received_in_update_bounds_ =
false;
173 transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
176 dyn_params_handler_ = node->add_on_set_parameters_callback(
179 this, std::placeholders::_1));
185 RCLCPP_DEBUG(logger_,
"StaticLayer: Process map");
187 unsigned int size_x = new_map.info.width;
188 unsigned int size_y = new_map.info.height;
192 "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
193 new_map.info.resolution);
200 master->
getOriginX() != new_map.info.origin.position.x ||
201 master->
getOriginY() != new_map.info.origin.position.y ||
207 "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
208 new_map.info.resolution);
210 size_x, size_y, new_map.info.resolution,
211 new_map.info.origin.position.x,
212 new_map.info.origin.position.y,
214 }
else if (size_x_ != size_x || size_y_ != size_y ||
215 resolution_ != new_map.info.resolution ||
216 origin_x_ != new_map.info.origin.position.x ||
217 origin_y_ != new_map.info.origin.position.y)
222 "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
223 new_map.info.resolution);
225 size_x, size_y, new_map.info.resolution,
226 new_map.info.origin.position.x, new_map.info.origin.position.y);
229 unsigned int index = 0;
232 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
235 for (
unsigned int i = 0; i < size_y; ++i) {
236 for (
unsigned int j = 0; j < size_x; ++j) {
237 unsigned char value = new_map.data[index];
243 map_frame_ = new_map.header.frame_id;
270 if (track_unknown_space_ && value == unknown_cost_value_) {
271 return NO_INFORMATION;
272 }
else if (!track_unknown_space_ && value == unknown_cost_value_) {
274 }
else if (value >= lethal_threshold_) {
275 return LETHAL_OBSTACLE;
276 }
else if (trinary_costmap_) {
280 double scale =
static_cast<double>(value) / lethal_threshold_;
281 return scale * LETHAL_OBSTACLE;
287 if (!nav2_util::validateMsg(*new_map)) {
288 RCLCPP_ERROR(logger_,
"Received map message is malformed. Rejecting.");
291 if (!map_received_) {
293 map_received_ =
true;
296 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
297 map_buffer_ = new_map;
303 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
304 if (update->y <
static_cast<int32_t
>(y_) ||
305 y_ + height_ < update->y + update->height ||
306 update->x <
static_cast<int32_t
>(x_) ||
307 x_ + width_ < update->x + update->width)
311 "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
312 "Static layer origin: %d, %d bounds: %d X %d\n"
313 "Update origin: %d, %d bounds: %d X %d",
314 x_, y_, width_, height_, update->x, update->y, update->width,
319 if (update->header.frame_id != map_frame_) {
322 "StaticLayer: Map update ignored. Current map is in frame %s "
323 "but update was in frame %s",
324 map_frame_.c_str(), update->header.frame_id.c_str());
329 for (
unsigned int y = 0; y < update->height; y++) {
330 unsigned int index_base = (update->y + y) * size_x_;
331 for (
unsigned int x = 0; x < update->width; x++) {
332 unsigned int index = index_base + x + update->x;
343 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
348 if (!map_received_) {
349 map_received_in_update_bounds_ =
false;
352 map_received_in_update_bounds_ =
true;
354 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
359 map_buffer_ =
nullptr;
368 useExtraBounds(min_x, min_y, max_x, max_y);
373 *min_x = std::min(wx, *min_x);
374 *min_y = std::min(wy, *min_y);
376 mapToWorld(x_ + width_, y_ + height_, wx, wy);
377 *max_x = std::max(wx, *max_x);
378 *max_y = std::max(wy, *max_y);
382 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
387 double robot_x,
double robot_y,
double robot_yaw,
388 double * min_x,
double * min_y,
392 if (!footprint_clearing_enabled_) {
return;}
396 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
397 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
404 int min_i,
int min_j,
int max_i,
int max_j)
406 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
410 if (!map_received_in_update_bounds_) {
411 static int count = 0;
414 RCLCPP_WARN(logger_,
"Can't update static costmap layer, no map received");
420 if (footprint_clearing_enabled_) {
427 updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
429 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
436 geometry_msgs::msg::TransformStamped transform;
438 transform = tf_->lookupTransform(
440 transform_tolerance_);
441 }
catch (tf2::TransformException & ex) {
442 RCLCPP_ERROR(logger_,
"StaticLayer: %s", ex.what());
446 tf2::Transform tf2_transform;
447 tf2::fromMsg(transform.transform, tf2_transform);
449 for (
int i = min_i; i < max_i; ++i) {
450 for (
int j = min_j; j < max_j; ++j) {
454 tf2::Vector3 p(wx, wy, 0);
455 p = tf2_transform * p;
474 rcl_interfaces::msg::SetParametersResult
476 std::vector<rclcpp::Parameter> parameters)
478 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
479 rcl_interfaces::msg::SetParametersResult result;
481 for (
auto parameter : parameters) {
482 const auto & param_type = parameter.get_type();
483 const auto & param_name = parameter.get_name();
485 if (param_name == name_ +
"." +
"map_subscribe_transient_local" ||
486 param_name == name_ +
"." +
"map_topic" ||
487 param_name == name_ +
"." +
"subscribe_to_updates")
490 logger_,
"%s is not a dynamic parameter "
491 "cannot be changed while running. Rejecting parameter update.", param_name.c_str());
492 }
else if (param_type == ParameterType::PARAMETER_DOUBLE) {
493 if (param_name == name_ +
"." +
"transform_tolerance") {
494 transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
496 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
497 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
498 enabled_ = parameter.as_bool();
505 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
506 footprint_clearing_enabled_ = parameter.as_bool();
510 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.
bool setConvexPolygonCost(const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
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.
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)