diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp index f805385573302..99a58eace1002 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp @@ -414,7 +414,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_map( } void VoxelGridDynamicMapLoader::timer_callback() { - std::optional current_position = std::nullopt; + std::optional current_position; { std::lock_guard lock(dynamic_map_loader_mutex_); current_position = current_position_; @@ -434,7 +434,7 @@ void VoxelGridDynamicMapLoader::timer_callback() bool VoxelGridDynamicMapLoader::should_update_map( const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point, - const double map_update_distance_threshold) const + const double map_update_distance_threshold) { if (distance2D(current_point, last_point) > map_update_distance_threshold) { return true; diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp index dbc1dbd6b6227..642cefe610e49 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp @@ -190,9 +190,9 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader void onEstimatedPoseCallback(nav_msgs::msg::Odometry::ConstSharedPtr msg); void timer_callback(); - bool should_update_map( + static bool should_update_map( const geometry_msgs::msg::Point & current_point, const geometry_msgs::msg::Point & last_point, - const double map_update_distance_threshold) const; + const double map_update_distance_threshold); void request_update_map(const geometry_msgs::msg::Point & position); bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override; /** \brief Check if point close to map pointcloud in the */