Skip to content

Commit

Permalink
fix: add region check
Browse files Browse the repository at this point in the history
Signed-off-by: Barış Zeren <[email protected]>
  • Loading branch information
StepTurtle committed Aug 27, 2024
1 parent fdc6e81 commit 30523b6
Showing 1 changed file with 14 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,15 @@ double norm_xy(const T & p1, const U & p2)
return std::hypot(dx, dy);
}

template <typename T>
bool is_inside_region(
const double & min_x, const double & max_x, const double & min_y, const double & max_y,
const T & point)
{
return min_x <= getX(point) && getX(point) <= max_x && min_y <= getY(point) &&
getY(point) <= max_y;
}

Check warning on line 63 in map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Excess Number of Function Arguments

is_inside_region has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

DynamicLaneletProviderNode::DynamicLaneletProviderNode(const rclcpp::NodeOptions & options)
: Node("dynamic_lanelet_provider", options),
map_frame_("map"),
Expand Down Expand Up @@ -129,6 +138,11 @@ void DynamicLaneletProviderNode::updateMap(const geometry_msgs::msg::Point & pos
point.x = (metadata.min_x + metadata.max_x) / 2;
point.y = (metadata.min_y + metadata.max_y) / 2;

if (is_inside_region(metadata.min_x, metadata.max_x, metadata.min_y, metadata.max_y, pose)) {
cache_ids.push_back(metadata.id);
continue;
}

double distance = norm_xy(point, pose);
if (distance < dynamic_map_loading_map_radius_) {
cache_ids.push_back(metadata.id);
Expand Down

0 comments on commit 30523b6

Please sign in to comment.