diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp index 330a3443b4e5d..826bdf5a8ed91 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp @@ -33,7 +33,7 @@ namespace autoware::behavior_velocity_planner namespace { RunOutDebug::TextWithPosition createDebugText( - const std::string text, const geometry_msgs::msg::Pose pose, const float lateral_offset) + const std::string & text, const geometry_msgs::msg::Pose pose, const float lateral_offset) { const auto offset_pose = autoware::universe_utils::calcOffsetPose(pose, 0, lateral_offset, 0); @@ -46,7 +46,7 @@ RunOutDebug::TextWithPosition createDebugText( visualization_msgs::msg::MarkerArray createPolygonMarkerArray( const std::vector> & poly, const rclcpp::Time & time, - const std::string ns, const geometry_msgs::msg::Vector3 & scale, + const std::string & ns, const geometry_msgs::msg::Vector3 & scale, const std_msgs::msg::ColorRGBA & color, const double height) { visualization_msgs::msg::MarkerArray marker_array; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index acb862f0eda70..0a38e8d47ea36 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -420,7 +420,7 @@ std::vector RunOutModule::excludeObstaclesOnEgoPath( std::vector RunOutModule::checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time, + const std::vector & poly, const float travel_time, const std::vector> & crosswalk_lanelets) const { const auto bg_poly_vehicle = run_out_utils::createBoostPolyFromMsg(poly); @@ -976,7 +976,7 @@ std::vector RunOutModule::excludeObstaclesOutSideOfPartition( } void RunOutModule::publishDebugValue( - const PathWithLaneId & path, const std::vector extracted_obstacles, + const PathWithLaneId & path, const std::vector & extracted_obstacles, const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose) const { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 1922cba9257ab..7d8513485ac52 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -87,7 +87,7 @@ class RunOutModule : public SceneModuleInterface std::vector checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time, + const std::vector & poly, const float travel_time, const std::vector> & crosswalk_lanelets) const; std::optional findNearestCollisionObstacle( @@ -171,7 +171,7 @@ class RunOutModule : public SceneModuleInterface const std::vector & dynamic_obstacles, const PathWithLaneId & path); void publishDebugValue( - const PathWithLaneId & path, const std::vector extracted_obstacles, + const PathWithLaneId & path, const std::vector & extracted_obstacles, const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose) const;