Skip to content

Commit

Permalink
fix(autoware_behavior_velocity_run_out_module): fix passedByValue (au…
Browse files Browse the repository at this point in the history
…towarefoundation#8215)

* fix:passedByValue

Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>

* fix:passedByValue

Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>

* fix:passedByValue

Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>

---------

Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
  • Loading branch information
kobayu858 authored Jul 29, 2024
1 parent 357d93c commit 0220122
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand All @@ -46,7 +46,7 @@ RunOutDebug::TextWithPosition createDebugText(

visualization_msgs::msg::MarkerArray createPolygonMarkerArray(
const std::vector<std::vector<geometry_msgs::msg::Point>> & 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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ std::vector<DynamicObstacle> RunOutModule::excludeObstaclesOnEgoPath(

std::vector<DynamicObstacle> RunOutModule::checkCollisionWithObstacles(
const std::vector<DynamicObstacle> & dynamic_obstacles,
std::vector<geometry_msgs::msg::Point> poly, const float travel_time,
const std::vector<geometry_msgs::msg::Point> & poly, const float travel_time,
const std::vector<std::pair<int64_t, lanelet::ConstLanelet>> & crosswalk_lanelets) const
{
const auto bg_poly_vehicle = run_out_utils::createBoostPolyFromMsg(poly);
Expand Down Expand Up @@ -976,7 +976,7 @@ std::vector<DynamicObstacle> RunOutModule::excludeObstaclesOutSideOfPartition(
}

void RunOutModule::publishDebugValue(
const PathWithLaneId & path, const std::vector<DynamicObstacle> extracted_obstacles,
const PathWithLaneId & path, const std::vector<DynamicObstacle> & extracted_obstacles,
const std::optional<DynamicObstacle> & dynamic_obstacle,
const geometry_msgs::msg::Pose & current_pose) const
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class RunOutModule : public SceneModuleInterface

std::vector<DynamicObstacle> checkCollisionWithObstacles(
const std::vector<DynamicObstacle> & dynamic_obstacles,
std::vector<geometry_msgs::msg::Point> poly, const float travel_time,
const std::vector<geometry_msgs::msg::Point> & poly, const float travel_time,
const std::vector<std::pair<int64_t, lanelet::ConstLanelet>> & crosswalk_lanelets) const;

std::optional<DynamicObstacle> findNearestCollisionObstacle(
Expand Down Expand Up @@ -171,7 +171,7 @@ class RunOutModule : public SceneModuleInterface
const std::vector<DynamicObstacle> & dynamic_obstacles, const PathWithLaneId & path);

void publishDebugValue(
const PathWithLaneId & path, const std::vector<DynamicObstacle> extracted_obstacles,
const PathWithLaneId & path, const std::vector<DynamicObstacle> & extracted_obstacles,
const std::optional<DynamicObstacle> & dynamic_obstacle,
const geometry_msgs::msg::Pose & current_pose) const;

Expand Down

0 comments on commit 0220122

Please sign in to comment.