Skip to content

Commit

Permalink
fix: add const
Browse files Browse the repository at this point in the history
Signed-off-by: h-ohta <hiroki.ota@tier4.jp>
  • Loading branch information
h-ohta committed Jan 25, 2022
1 parent abba760 commit c67dcb9
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,11 +48,11 @@ class MapBasedPrediction
const double height, const double current_d_position, const double current_d_velocity,
const double current_s_position, const double current_s_velocity,
const std_msgs::msg::Header & origin_header, Spline2D & spline2d,
autoware_auto_perception_msgs::msg::PredictedPath & path);
autoware_auto_perception_msgs::msg::PredictedPath & path) const;

void getLinearPredictedPath(
const geometry_msgs::msg::Pose & object_pose, const geometry_msgs::msg::Twist & object_twist,
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path);
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path) const;

void normalizeLikelihood(
autoware_auto_perception_msgs::msg::PredictedObjectKinematics & predicted_object_kinematics);
Expand Down
4 changes: 2 additions & 2 deletions perception/map_based_prediction/src/map_based_prediction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ bool MapBasedPrediction::getPredictedPath(
const double height, const double current_d_position, const double current_d_velocity,
const double current_s_position, const double current_s_velocity,
[[maybe_unused]] const std_msgs::msg::Header & origin_header, Spline2D & spline2d,
autoware_auto_perception_msgs::msg::PredictedPath & path)
autoware_auto_perception_msgs::msg::PredictedPath & path) const
{
// Quintic polynomial for d
// A = np.array([[T**3, T**4, T**5],
Expand Down Expand Up @@ -269,7 +269,7 @@ bool MapBasedPrediction::getPredictedPath(

void MapBasedPrediction::getLinearPredictedPath(
const geometry_msgs::msg::Pose & object_pose, const geometry_msgs::msg::Twist & object_twist,
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path)
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path) const
{
const double & sampling_delta_time = sampling_delta_time_;
const double & time_horizon = time_horizon_;
Expand Down

0 comments on commit c67dcb9

Please sign in to comment.