Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and zulfaqar-azmi-t4 committed Apr 8, 2024
1 parent 69ff2f3 commit abd170b
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 9 deletions.
18 changes: 11 additions & 7 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1955,12 +1955,16 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
}

const auto extenal_velocity_limit_ptr = planner_data_->external_limit_max_velocity;

Check warning on line 1957 in planning/behavior_path_lane_change_module/src/scene.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (extenal)
const auto max_velocity_limit = (extenal_velocity_limit_ptr) ? std::min(static_cast<double>(extenal_velocity_limit_ptr->max_velocity), getCommonParam().max_vel) : getCommonParam().max_vel;
const auto max_velocity_limit =
(extenal_velocity_limit_ptr)

Check warning on line 1959 in planning/behavior_path_lane_change_module/src/scene.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (extenal)
? std::min(
static_cast<double>(extenal_velocity_limit_ptr->max_velocity), getCommonParam().max_vel)

Check warning on line 1961 in planning/behavior_path_lane_change_module/src/scene.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (extenal)
: getCommonParam().max_vel;

const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
lane_change_path.info.target_lanes, direction_,
lane_change_parameters_->lane_expansion_left_offset,
lane_change_parameters_->lane_expansion_right_offset);
const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
lane_change_path.info.target_lanes, direction_,
lane_change_parameters_->lane_expansion_left_offset,
lane_change_parameters_->lane_expansion_right_offset);

for (const auto & obj : collision_check_objects) {
auto current_debug_data = utils::path_safety_checker::createObjectDebug(obj);
Expand All @@ -1969,8 +1973,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
auto is_safe = true;
for (const auto & obj_path : obj_predicted_paths) {
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, max_velocity_limit,
current_debug_data.second);
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
max_velocity_limit, current_debug_data.second);

Check warning on line 1977 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

NormalLaneChange::isLaneChangePathSafe increases in cyclomatic complexity from 12 to 13, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

if (collided_polygons.empty()) {
utils::path_safety_checker::updateCollisionCheckDebugMap(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include <tier4_autoware_utils/ros/update_param.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/path_change_module_id.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>

#include <functional>
#include <memory>
Expand Down Expand Up @@ -828,7 +828,7 @@ void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSha
void BehaviorPathPlannerNode::on_external_velocity_limiter(
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg)
{
if(!msg){
if (!msg) {
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <boost/geometry/algorithms/overlaps.hpp>
#include <boost/geometry/algorithms/union.hpp>
#include <boost/geometry/strategies/strategies.hpp>

#include <limits>

namespace behavior_path_planner::utils::path_safety_checker
Expand Down

0 comments on commit abd170b

Please sign in to comment.