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"
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));
144 auto node = node_.lock();
146 throw std::runtime_error{
"Failed to lock node"};
149 node->get_parameter(name_ +
"." +
"enabled", enabled_);
150 node->get_parameter(name_ +
"." +
"subscribe_to_updates", subscribe_to_updates_);
151 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
152 std::string private_map_topic, global_map_topic;
153 node->get_parameter(name_ +
"." +
"map_topic", private_map_topic);
154 node->get_parameter(
"map_topic", global_map_topic);
155 if (!private_map_topic.empty()) {
156 map_topic_ = private_map_topic;
158 map_topic_ = global_map_topic;
161 name_ +
"." +
"map_subscribe_transient_local",
162 map_subscribe_transient_local_);
163 node->get_parameter(
"track_unknown_space", track_unknown_space_);
164 node->get_parameter(
"use_maximum", use_maximum_);
165 node->get_parameter(
"lethal_cost_threshold", temp_lethal_threshold);
166 node->get_parameter(
"unknown_cost_value", unknown_cost_value_);
167 node->get_parameter(
"trinary_costmap", trinary_costmap_);
168 node->get_parameter(
"transform_tolerance", temp_tf_tol);
171 lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
172 map_received_ =
false;
173 map_received_in_update_bounds_ =
false;
175 transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
178 dyn_params_handler_ = node->add_on_set_parameters_callback(
181 this, std::placeholders::_1));
187 RCLCPP_DEBUG(logger_,
"StaticLayer: Process map");
189 unsigned int size_x = new_map.info.width;
190 unsigned int size_y = new_map.info.height;
194 "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
195 new_map.info.resolution);
209 "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
210 new_map.info.resolution);
212 size_x, size_y, new_map.info.resolution,
213 new_map.info.origin.position.x,
214 new_map.info.origin.position.y,
216 }
else if (size_x_ != size_x || size_y_ != size_y ||
217 !
isEqual(resolution_, new_map.info.resolution, EPSILON) ||
218 !
isEqual(origin_x_, new_map.info.origin.position.x, EPSILON) ||
219 !
isEqual(origin_y_, new_map.info.origin.position.y, EPSILON))
224 "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
225 new_map.info.resolution);
227 size_x, size_y, new_map.info.resolution,
228 new_map.info.origin.position.x, new_map.info.origin.position.y);
231 unsigned int index = 0;
234 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
237 for (
unsigned int i = 0; i < size_y; ++i) {
238 for (
unsigned int j = 0; j < size_x; ++j) {
239 unsigned char value = new_map.data[index];
245 map_frame_ = new_map.header.frame_id;
272 if (track_unknown_space_ && value == unknown_cost_value_) {
273 return NO_INFORMATION;
274 }
else if (!track_unknown_space_ && value == unknown_cost_value_) {
276 }
else if (value >= lethal_threshold_) {
277 return LETHAL_OBSTACLE;
278 }
else if (trinary_costmap_) {
282 double scale =
static_cast<double>(value) / lethal_threshold_;
283 return scale * LETHAL_OBSTACLE;
289 if (!nav2_util::validateMsg(*new_map)) {
290 RCLCPP_ERROR(logger_,
"Received map message is malformed. Rejecting.");
293 if (!map_received_) {
295 map_received_ =
true;
298 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
299 map_buffer_ = new_map;
305 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
306 if (update->y <
static_cast<int32_t
>(y_) ||
307 y_ + height_ < update->y + update->height ||
308 update->x <
static_cast<int32_t
>(x_) ||
309 x_ + width_ < update->x + update->width)
313 "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
314 "Static layer origin: %d, %d bounds: %d X %d\n"
315 "Update origin: %d, %d bounds: %d X %d",
316 x_, y_, width_, height_, update->x, update->y, update->width,
321 if (update->header.frame_id != map_frame_) {
324 "StaticLayer: Map update ignored. Current map is in frame %s "
325 "but update was in frame %s",
326 map_frame_.c_str(), update->header.frame_id.c_str());
331 for (
unsigned int y = 0; y < update->height; y++) {
332 unsigned int index_base = (update->y + y) * size_x_;
333 for (
unsigned int x = 0; x < update->width; x++) {
334 unsigned int index = index_base + x + update->x;
345 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
350 if (!map_received_) {
351 map_received_in_update_bounds_ =
false;
354 map_received_in_update_bounds_ =
true;
356 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
361 map_buffer_ =
nullptr;
370 useExtraBounds(min_x, min_y, max_x, max_y);
375 *min_x = std::min(wx, *min_x);
376 *min_y = std::min(wy, *min_y);
378 mapToWorld(x_ + width_, y_ + height_, wx, wy);
379 *max_x = std::max(wx, *max_x);
380 *max_y = std::max(wy, *max_y);
384 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
389 double robot_x,
double robot_y,
double robot_yaw,
390 double * min_x,
double * min_y,
394 if (!footprint_clearing_enabled_) {
return;}
398 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
399 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
406 int min_i,
int min_j,
int max_i,
int max_j)
408 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
412 if (!map_received_in_update_bounds_) {
413 static int count = 0;
416 RCLCPP_WARN(logger_,
"Can't update static costmap layer, no map received");
422 if (footprint_clearing_enabled_) {
429 updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
431 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
438 geometry_msgs::msg::TransformStamped transform;
440 transform = tf_->lookupTransform(
442 transform_tolerance_);
443 }
catch (tf2::TransformException & ex) {
444 RCLCPP_ERROR(logger_,
"StaticLayer: %s", ex.what());
448 tf2::Transform tf2_transform;
449 tf2::fromMsg(transform.transform, tf2_transform);
451 for (
int i = min_i; i < max_i; ++i) {
452 for (
int j = min_j; j < max_j; ++j) {
456 tf2::Vector3 p(wx, wy, 0);
457 p = tf2_transform * p;
481 return std::abs(a - b) < epsilon;
488 rcl_interfaces::msg::SetParametersResult
490 std::vector<rclcpp::Parameter> parameters)
492 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
493 rcl_interfaces::msg::SetParametersResult result;
495 for (
auto parameter : parameters) {
496 const auto & param_type = parameter.get_type();
497 const auto & param_name = parameter.get_name();
499 if (param_name == name_ +
"." +
"map_subscribe_transient_local" ||
500 param_name == name_ +
"." +
"map_topic" ||
501 param_name == name_ +
"." +
"subscribe_to_updates")
504 logger_,
"%s is not a dynamic parameter "
505 "cannot be changed while running. Rejecting parameter update.", param_name.c_str());
506 }
else if (param_type == ParameterType::PARAMETER_DOUBLE) {
507 if (param_name == name_ +
"." +
"transform_tolerance") {
508 transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
510 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
511 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
512 enabled_ = parameter.as_bool();
519 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
520 footprint_clearing_enabled_ = parameter.as_bool();
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.
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...
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)