diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp index ee2eadac6f780..82a4d5a7ec550 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -111,16 +111,6 @@ double getDistanceFromTwoPoint( } } -constexpr double sign(const double value) -{ - if (value > 0) { - return 1.0; - } else if (value < 0) { - return -1.0; - } else { - return 0.0; - } -} } // namespace namespace autoware::motion_planning @@ -573,7 +563,7 @@ double AdaptiveCruiseController::calcUpperVelocity( } double AdaptiveCruiseController::calcThreshDistToForwardObstacle( - const double current_vel, const double obj_vel) + const double current_vel, const double obj_vel) const { const double current_vel_min = std::max(1.0, std::fabs(current_vel)); const double obj_vel_min = std::max(0.0, obj_vel); @@ -590,7 +580,7 @@ double AdaptiveCruiseController::calcThreshDistToForwardObstacle( } double AdaptiveCruiseController::calcBaseDistToForwardObstacle( - const double current_vel, const double obj_vel) + const double current_vel, const double obj_vel) const { const double obj_vel_min = std::max(0.0, obj_vel); const double minimum_distance = param_.min_dist_standard; diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp index 7535986f1db85..ce57f585197ad 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp @@ -203,8 +203,8 @@ class AdaptiveCruiseController double estimateRoughPointVelocity(double current_vel); bool isObstacleVelocityHigh(const double obj_vel); double calcUpperVelocity(const double dist_to_col, const double obj_vel, const double self_vel); - double calcThreshDistToForwardObstacle(const double current_vel, const double obj_vel); - double calcBaseDistToForwardObstacle(const double current_vel, const double obj_vel); + double calcThreshDistToForwardObstacle(const double current_vel, const double obj_vel) const; + double calcBaseDistToForwardObstacle(const double current_vel, const double obj_vel) const; double calcTargetVelocity_P(const double target_dist, const double current_dist) const; static double calcTargetVelocity_I(const double target_dist, const double current_dist); double calcTargetVelocity_D(const double target_dist, const double current_dist); diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index ac043dd895ea7..4400368cc3d70 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -77,7 +77,7 @@ class DebugValues * @brief get all the debug values as an std::array * @return array of all debug values */ - std::array(TYPE::SIZE)> getValues() const { return values_; } + const std::array(TYPE::SIZE)> & getValues() const { return values_; } /** * @brief set the given type to the given value * @param [in] type TYPE of the value