Skip to content

Commit fba0358

Browse files
doisygGuillaume Doisy
andauthored
[static_layer] limit comparison precision (#5405)
* [DEX] limit comparison precision Signed-off-by: Guillaume Doisy <guillaume@dexory.com> * EPSILON 1e-5 Signed-off-by: Guillaume Doisy <guillaume@dexory.com> --------- Signed-off-by: Guillaume Doisy <guillaume@dexory.com> Co-authored-by: Guillaume Doisy <guillaume@dexory.com>
1 parent f07bfc6 commit fba0358

File tree

2 files changed

+29
-6
lines changed

2 files changed

+29
-6
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -153,6 +153,15 @@ class StaticLayer : public CostmapLayer
153153
*/
154154
unsigned char interpretValue(unsigned char value);
155155

156+
/**
157+
* @brief Check if two double values are equal within a given epsilon
158+
* @param a First double value
159+
* @param b Second double value
160+
* @param epsilon The tolerance for equality check
161+
* @return True if the values are equal within the tolerance, false otherwise
162+
*/
163+
bool isEqual(double a, double b, double epsilon);
164+
156165
/**
157166
* @brief Callback executed when a parameter change is detected
158167
* @param event ParameterEvent message

nav2_costmap_2d/plugins/static_layer.cpp

Lines changed: 20 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@
4747
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
4848
#include "nav2_ros_common/validate_messages.hpp"
4949

50+
#define EPSILON 1e-5
51+
5052
PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)
5153

5254
using 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

Comments
 (0)