Skip to content

Commit

Permalink
fix(autoware_obstacle_stop_planner): fix passedByValue (autowarefound…
Browse files Browse the repository at this point in the history
…ation#8189)

fix:passedByValue

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Aug 2, 2024
1 parent b00e8e9 commit f105db9
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -748,7 +748,7 @@ void AdaptiveCruiseController::registerQueToVelocity(
est_vel_que_.emplace_back(new_vel);
}

double AdaptiveCruiseController::getMedianVel(const std::vector<nav_msgs::msg::Odometry> vel_que)
double AdaptiveCruiseController::getMedianVel(const std::vector<nav_msgs::msg::Odometry> & vel_que)
{
if (vel_que.size() == 0) {
RCLCPP_WARN_STREAM(node_->get_logger(), "size of vel que is 0. Something has wrong.");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ class AdaptiveCruiseController
};
Param param_;

double getMedianVel(const std::vector<nav_msgs::msg::Odometry> vel_que);
double getMedianVel(const std::vector<nav_msgs::msg::Odometry> & vel_que);
double lowpass_filter(const double current_value, const double prev_value, const double gain);
void calcDistanceToNearestPointOnPath(
const TrajectoryPoints & trajectory, const int nearest_point_idx,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ std::string jsonDumpsPose(const Pose & pose)
return json_dumps_pose;
}

DiagnosticStatus makeStopReasonDiag(const std::string stop_reason, const Pose & stop_pose)
DiagnosticStatus makeStopReasonDiag(const std::string & stop_reason, const Pose & stop_pose)
{
DiagnosticStatus stop_reason_diag;
KeyValue stop_reason_diag_kv;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ Polygon2d convertBoundingBoxObjectToGeometryPolygon(

std::string jsonDumpsPose(const Pose & pose);

DiagnosticStatus makeStopReasonDiag(const std::string stop_reason, const Pose & stop_pose);
DiagnosticStatus makeStopReasonDiag(const std::string & stop_reason, const Pose & stop_pose);

TrajectoryPoint getBackwardPointFromBasePoint(
const TrajectoryPoint & p_from, const TrajectoryPoint & p_to, const TrajectoryPoint & p_base,
Expand Down

0 comments on commit f105db9

Please sign in to comment.