Skip to content

Commit

Permalink
fix: CI error
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Mar 6, 2025
1 parent 52c5459 commit 4cf4db0
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
}
void VoxelGridDynamicMapLoader::timer_callback()
{
std::optional<geometry_msgs::msg::Point> current_position = std::nullopt;
std::optional<geometry_msgs::msg::Point> current_position;

Check warning on line 417 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L417

Added line #L417 was not covered by tests
{
std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
current_position = current_position_;

Check warning on line 420 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L419-L420

Added lines #L419 - L420 were not covered by tests
Expand All @@ -434,7 +434,7 @@ void VoxelGridDynamicMapLoader::timer_callback()

bool VoxelGridDynamicMapLoader::should_update_map(

Check warning on line 435 in perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp#L435

Added line #L435 was not covered by tests
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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down

0 comments on commit 4cf4db0

Please sign in to comment.