Skip to content

Commit

Permalink
Rename parameters
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Mar 20, 2024
1 parent 8c10227 commit 44c187b
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,8 @@ struct LaneChangeParameters
double max_longitudinal_acc{1.0};

// collision check
bool enable_prepare_segment_collision_check_in_general_areas{false};
bool enable_prepare_segment_collision_check_in_intersection{true};
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
bool enable_collision_check_for_prepare_phase_in_intersection{true};
double prepare_segment_ignore_object_velocity_thresh{0.1};
bool check_objects_on_current_lanes{true};
bool check_objects_on_other_lanes{true};
Expand Down
8 changes: 4 additions & 4 deletions planning/behavior_path_lane_change_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,10 +68,10 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
p.max_longitudinal_acc = getOrDeclareParameter<double>(*node, parameter("max_longitudinal_acc"));

// collision check
p.enable_prepare_segment_collision_check_in_general_areas = getOrDeclareParameter<bool>(
*node, parameter("enable_prepare_segment_collision_check.general_areas"));
p.enable_prepare_segment_collision_check_in_intersection = getOrDeclareParameter<bool>(
*node, parameter("enable_prepare_segment_collision_check.intersection"));
p.enable_collision_check_for_prepare_phase_in_general_lanes = getOrDeclareParameter<bool>(
*node, parameter("enable_collision_check_for_prepare_phase.general_lanes"));
p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter<bool>(
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
p.check_objects_on_current_lanes =
Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2091,7 +2091,7 @@ bool NormalLaneChange::check_prepare_phase() const
const auto & vehicle_info = getCommonParam().vehicle_info;

const auto check_prepare_phase_in_intersection = std::invoke([&]() {
if (!lane_change_parameters_->enable_prepare_segment_collision_check_in_intersection) {
if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_intersection) {
return false;
}

Expand All @@ -2107,7 +2107,7 @@ bool NormalLaneChange::check_prepare_phase() const
});

return check_prepare_phase_in_intersection ||
lane_change_parameters_->enable_prepare_segment_collision_check_in_general_areas;
lane_change_parameters_->enable_collision_check_for_prepare_phase_in_general_lanes;
}

} // namespace behavior_path_planner

0 comments on commit 44c187b

Please sign in to comment.