Skip to content

Commit

Permalink
fix(autoware_obstacle_stop_planner): fix cppcheck warnings (#9388)
Browse files Browse the repository at this point in the history
Signed-off-by: Ryuta Kambe <[email protected]>
  • Loading branch information
veqcc authored Nov 20, 2024
1 parent 3a1ae3b commit f22096a
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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);
Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class DebugValues
* @brief get all the debug values as an std::array
* @return array of all debug values
*/
std::array<double, static_cast<int>(TYPE::SIZE)> getValues() const { return values_; }
const std::array<double, static_cast<int>(TYPE::SIZE)> & getValues() const { return values_; }
/**
* @brief set the given type to the given value
* @param [in] type TYPE of the value
Expand Down

0 comments on commit f22096a

Please sign in to comment.