Skip to content

Commit

Permalink
missing dot
Browse files Browse the repository at this point in the history
Signed-off-by: Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Jan 16, 2025
1 parent d4e1c0d commit 349aa58
Showing 1 changed file with 3 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s
params.lateral_distance_max_threshold =
getOrDeclareParameter<double>(*node, parameter(prefix + ".lateral_distance_max_threshold"));
params.extended_polygon_policy =
getOrDeclareParameter<std::string>(*node, parameter(prefix + "extended_polygon_policy"));
getOrDeclareParameter<std::string>(*node, parameter(prefix + ".extended_polygon_policy"));

Check warning on line 175 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

LaneChangeModuleManager::set_params already has high cyclomatic complexity, and now it increases in Lines of Code from 213 to 217. 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.
};
set_rss_params(p.safety.rss_params, "safety_check.execution");
set_rss_params(p.safety.rss_params_for_parked, "safety_check.parked");
Expand Down Expand Up @@ -452,7 +452,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
} else {
RCLCPP_WARN_THROTTLE(

Check warning on line 453 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp#L453

Added line #L453 was not covered by tests
node_->get_logger(), *node_->get_clock(), 5000,
"The value of th_incoming_object_yaw (%.3f rad) is less than the minimum possible value (%.3f "
"The value of th_incoming_object_yaw (%.3f rad) is less than the minimum possible value "
"(%.3f "
"rad).",
th_incoming_object_yaw, M_PI_2);
}
Expand Down

0 comments on commit 349aa58

Please sign in to comment.