Skip to content

Commit af20396

Browse files
author
beyza
committed
update function's arguments
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent afd0a1a commit af20396

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop
2929
/// @return the collision point closest to ego (if any)
3030
std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
3131
const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose,
32-
const tier4_autoware_utils::Polygon2d & object_footprint);
32+
const tier4_autoware_utils::Polygon2d & object_footprint, const PlannerParam & params);
3333

3434
/// @brief find the earliest collision along the ego path
3535
/// @param [in] ego_data ego data including its path and footprint
@@ -39,7 +39,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
3939
std::vector<Collision> find_collisions(
4040
const EgoData & ego_data,
4141
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
42-
const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints);
42+
const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, const PlannerParam & params);
4343

4444
} // namespace behavior_velocity_planner::dynamic_obstacle_stop
4545

planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
9191
make_forward_footprints(dynamic_obstacles, params_, hysteresis);
9292
const auto footprints_duration_us = stopwatch.toc("footprints");
9393
stopwatch.tic("collisions");
94-
auto collisions = find_collisions(ego_data, dynamic_obstacles, obstacle_forward_footprints);
94+
auto collisions = find_collisions(ego_data, dynamic_obstacles, obstacle_forward_footprints, params_);
9595
update_object_map(object_map_, collisions, clock_->now(), ego_data.path.points, params_);
9696
std::optional<geometry_msgs::msg::Point> earliest_collision =
9797
find_earliest_collision(object_map_, ego_data);

0 commit comments

Comments
 (0)