Skip to content

Commit f85bf32

Browse files
authored
fix(behavior_path_planner_common): swap boolean for filterObjectsByVelocity (autowarefoundation#9036)
fix filter object by velocity Signed-off-by: Go Sakayori <go.sakayori@tier4.jp>
1 parent 1e26395 commit f85bf32

File tree

4 files changed

+5
-5
lines changed

4 files changed

+5
-5
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -2162,7 +2162,7 @@ static std::vector<utils::path_safety_checker::ExtendedPredictedObject> filterOb
21622162
const auto & target_object_types = params->object_types_to_check;
21632163

21642164
PredictedObjects filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
2165-
*objects, ignore_object_velocity_threshold, false);
2165+
*objects, ignore_object_velocity_threshold, true);
21662166

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

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ PredictedObjects filterObjects(
113113
*/
114114
PredictedObjects filterObjectsByVelocity(
115115
const PredictedObjects & objects, const double velocity_threshold,
116-
const bool remove_above_threshold = true);
116+
const bool remove_above_threshold = false);
117117

118118
/**
119119
* @brief Helper function to filter objects based on their velocity.

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ PredictedObjects filterObjects(
118118
const ObjectTypesToCheck & target_object_types = params->object_types_to_check;
119119

120120
PredictedObjects filtered_objects =
121-
filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, false);
121+
filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, true);
122122

123123
filterObjectsByClass(filtered_objects, target_object_types);
124124

@@ -136,7 +136,7 @@ PredictedObjects filterObjectsByVelocity(
136136
const PredictedObjects & objects, const double velocity_threshold,
137137
const bool remove_above_threshold)
138138
{
139-
if (remove_above_threshold) {
139+
if (!remove_above_threshold) {
140140
return filterObjectsByVelocity(objects, -velocity_threshold, velocity_threshold);
141141
}
142142
return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits<double>::max());

planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -329,7 +329,7 @@ bool StartPlannerModule::noMovingObjectsAround() const
329329
utils::path_safety_checker::filterObjectsByClass(
330330
dynamic_objects, parameters_->surround_moving_obstacles_type_to_check);
331331
const auto filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
332-
dynamic_objects, parameters_->th_moving_obstacle_velocity, false);
332+
dynamic_objects, parameters_->th_moving_obstacle_velocity, true);
333333
if (!filtered_objects.objects.empty()) {
334334
DEBUG_PRINT("Moving objects exist in the safety check area");
335335
}

0 commit comments

Comments
 (0)