Skip to content

Commit

Permalink
fix(behavior_path_planner_common): swap boolean for filterObjectsByVe…
Browse files Browse the repository at this point in the history
…locity (autowarefoundation#9036)

fix filter object by velocity

Signed-off-by: Go Sakayori <[email protected]>
Signed-off-by: prakash-kannaiah <[email protected]>
  • Loading branch information
go-sakayori authored and prakash-kannaiah committed Oct 9, 2024
1 parent 5fe7b5e commit 5d4b6ac
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2162,7 +2162,7 @@ static std::vector<utils::path_safety_checker::ExtendedPredictedObject> filterOb
const auto & target_object_types = params->object_types_to_check;

PredictedObjects filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
*objects, ignore_object_velocity_threshold, false);
*objects, ignore_object_velocity_threshold, true);

utils::path_safety_checker::filterObjectsByClass(filtered_objects, target_object_types);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ PredictedObjects filterObjects(
*/
PredictedObjects filterObjectsByVelocity(
const PredictedObjects & objects, const double velocity_threshold,
const bool remove_above_threshold = true);
const bool remove_above_threshold = false);

/**
* @brief Helper function to filter objects based on their velocity.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ PredictedObjects filterObjects(
const ObjectTypesToCheck & target_object_types = params->object_types_to_check;

PredictedObjects filtered_objects =
filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, false);
filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, true);

filterObjectsByClass(filtered_objects, target_object_types);

Expand All @@ -136,7 +136,7 @@ PredictedObjects filterObjectsByVelocity(
const PredictedObjects & objects, const double velocity_threshold,
const bool remove_above_threshold)
{
if (remove_above_threshold) {
if (!remove_above_threshold) {
return filterObjectsByVelocity(objects, -velocity_threshold, velocity_threshold);
}
return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits<double>::max());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ bool StartPlannerModule::noMovingObjectsAround() const
utils::path_safety_checker::filterObjectsByClass(
dynamic_objects, parameters_->surround_moving_obstacles_type_to_check);
const auto filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
dynamic_objects, parameters_->th_moving_obstacle_velocity, false);
dynamic_objects, parameters_->th_moving_obstacle_velocity, true);
if (!filtered_objects.objects.empty()) {
DEBUG_PRINT("Moving objects exist in the safety check area");
}
Expand Down

0 comments on commit 5d4b6ac

Please sign in to comment.