4747#include " tf2_geometry_msgs/tf2_geometry_msgs.hpp"
4848#include " nav2_ros_common/validate_messages.hpp"
4949
50+ #define EPSILON 1e-5
51+
5052PLUGINLIB_EXPORT_CLASS (nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)
5153
5254using nav2_costmap_2d::NO_INFORMATION;
@@ -190,9 +192,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
190192 Costmap2D * master = layered_costmap_->getCostmap ();
191193 if (!layered_costmap_->isRolling () && (master->getSizeInCellsX () != size_x ||
192194 master->getSizeInCellsY () != size_y ||
193- master->getResolution () != new_map.info .resolution ||
194- master->getOriginX () != new_map.info .origin .position .x ||
195- master->getOriginY () != new_map.info .origin .position .y ||
195+ ! isEqual ( master->getResolution (), new_map.info .resolution , EPSILON) ||
196+ ! isEqual ( master->getOriginX (), new_map.info .origin .position .x , EPSILON) ||
197+ ! isEqual ( master->getOriginY (), new_map.info .origin .position .y , EPSILON) ||
196198 !layered_costmap_->isSizeLocked ()))
197199 {
198200 // Update the size of the layered costmap (and all layers, including this one)
@@ -206,9 +208,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
206208 new_map.info .origin .position .y ,
207209 true );
208210 } else if (size_x_ != size_x || size_y_ != size_y || // NOLINT
209- resolution_ != new_map.info .resolution ||
210- origin_x_ != new_map.info .origin .position .x ||
211- origin_y_ != new_map.info .origin .position .y )
211+ ! isEqual ( resolution_, new_map.info .resolution , EPSILON) ||
212+ ! isEqual ( origin_x_, new_map.info .origin .position .x , EPSILON) ||
213+ ! isEqual ( origin_y_, new_map.info .origin .position .y , EPSILON) )
212214 {
213215 // only update the size of the costmap stored locally in this layer
214216 RCLCPP_INFO (
@@ -469,6 +471,18 @@ StaticLayer::updateCosts(
469471 current_ = true ;
470472}
471473
474+ /* *
475+ * @brief Check if two floating point numbers are equal within a given epsilon
476+ * @param a First number
477+ * @param b Second number
478+ * @param epsilon Tolerance for equality check
479+ * @return True if numbers are equal within the tolerance, false otherwise
480+ */
481+ bool StaticLayer::isEqual (double a, double b, double epsilon)
482+ {
483+ return std::abs (a - b) < epsilon;
484+ }
485+
472486/* *
473487 * @brief Callback executed when a parameter change is detected
474488 * @param event ParameterEvent message
0 commit comments