Skip to content

Commit

Permalink
ensure param update value is valid
Browse files Browse the repository at this point in the history
Signed-off-by: mohammad alqudah <[email protected]>
  • Loading branch information
mkquda committed Jan 15, 2025
1 parent eaf0b57 commit 9553e72
Showing 1 changed file with 29 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -314,7 +314,17 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param

{
const std::string ns = "lane_change.";
updateParam<double>(parameters, ns + "time_limit", p->time_limit);
auto time_limit = p->time_limit;
updateParam<double>(parameters, ns + "time_limit", time_limit);
if (time_limit >= 10.0) {
p->time_limit = time_limit;
} else {
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"WARNING! Parameter 'time_limit' is not updated becasue the value (%.3f ms) is not valid, "

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Misspelled word (becasue) Suggestions: (because*)
"keep current value (%.3f ms)",
time_limit, p->time_limit);
}
updateParam<double>(parameters, ns + "backward_lane_length", p->backward_lane_length);
updateParam<double>(
parameters, ns + "backward_length_buffer_for_end_of_lane",
Expand Down Expand Up @@ -356,9 +366,10 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
if (longitudinal_acc_sampling_num > 0) {
p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num;
} else {
RCLCPP_WARN_ONCE(
node_->get_logger(),
"Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not positive",
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"WARNING! Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not "
"positive",
longitudinal_acc_sampling_num);
}

Expand All @@ -367,9 +378,10 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
if (lateral_acc_sampling_num > 0) {
p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num;
} else {
RCLCPP_WARN_ONCE(
node_->get_logger(),
"Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not positive",
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"WARNING! Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not "
"positive",
lateral_acc_sampling_num);
}

Expand Down Expand Up @@ -411,8 +423,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
}
p->trajectory.lat_acc_map = lat_acc_map;
} else {
RCLCPP_WARN_ONCE(
node_->get_logger(),
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"Mismatched size for lateral acceleration. Expected size: %lu, but velocity: %lu, "
"min_values: %lu, max_values: %lu",
std::max(2ul, velocity.size()), velocity.size(), min_values.size(), max_values.size());
Expand Down Expand Up @@ -520,15 +532,19 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
bool enable_on_prepare_phase = true;
updateParam<bool>(parameters, ns + "enable_on_prepare_phase", enable_on_prepare_phase);
if (!enable_on_prepare_phase) {
RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change cancel function is disabled.");
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"WARNING! Lane Change cancel function is disabled.");
p->cancel.enable_on_prepare_phase = enable_on_prepare_phase;
}

bool enable_on_lane_changing_phase = true;
updateParam<bool>(
parameters, ns + "enable_on_lane_changing_phase", enable_on_lane_changing_phase);
if (!enable_on_lane_changing_phase) {
RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change abort function is disabled.");
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,
"WARNING! Lane Change abort function is disabled.");
p->cancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase;
}

Expand All @@ -537,8 +553,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
if (deceleration_sampling_num > 0) {
p->cancel.deceleration_sampling_num = deceleration_sampling_num;
} else {
RCLCPP_WARN_ONCE(
node_->get_logger(),
RCLCPP_WARN_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000,

Check warning on line 557 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::updateModuleParams increases in cyclomatic complexity from 11 to 12, 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.
"Parameter 'deceleration_sampling_num' is not updated because the value (%d) is not "
"positive",
deceleration_sampling_num);
Expand Down

0 comments on commit 9553e72

Please sign in to comment.