Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_obstacle_stop_planner): fix cppcheck warnings #9388

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 50.65% to 47.22%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -111,16 +111,6 @@
}
}

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::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::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
Loading