Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,15 @@ class StaticLayer : public CostmapLayer
*/
unsigned char interpretValue(unsigned char value);

/**
* @brief Check if two double values are equal within a given epsilon
* @param a First double value
* @param b Second double value
* @param epsilon The tolerance for equality check
* @return True if the values are equal within the tolerance, false otherwise
*/
bool isEqual(double a, double b, double epsilon);

/**
* @brief Callback executed when a parameter change is detected
* @param event ParameterEvent message
Expand Down
26 changes: 20 additions & 6 deletions nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_ros_common/validate_messages.hpp"

#define EPSILON 1e-5

PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)

using nav2_costmap_2d::NO_INFORMATION;
Expand Down Expand Up @@ -190,9 +192,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
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 ||
!isEqual(master->getResolution(), new_map.info.resolution, EPSILON) ||
!isEqual(master->getOriginX(), new_map.info.origin.position.x, EPSILON) ||
!isEqual(master->getOriginY(), new_map.info.origin.position.y, EPSILON) ||
!layered_costmap_->isSizeLocked()))
{
// Update the size of the layered costmap (and all layers, including this one)
Expand All @@ -206,9 +208,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
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)
!isEqual(resolution_, new_map.info.resolution, EPSILON) ||
!isEqual(origin_x_, new_map.info.origin.position.x, EPSILON) ||
!isEqual(origin_y_, new_map.info.origin.position.y, EPSILON))
{
// only update the size of the costmap stored locally in this layer
RCLCPP_INFO(
Expand Down Expand Up @@ -469,6 +471,18 @@ StaticLayer::updateCosts(
current_ = true;
}

/**
* @brief Check if two floating point numbers are equal within a given epsilon
* @param a First number
* @param b Second number
* @param epsilon Tolerance for equality check
* @return True if numbers are equal within the tolerance, false otherwise
*/
bool StaticLayer::isEqual(double a, double b, double epsilon)
{
return std::abs(a - b) < epsilon;
}

/**
* @brief Callback executed when a parameter change is detected
* @param event ParameterEvent message
Expand Down
Loading