Skip to content

Commit

Permalink
refactor(lane_change): rename prepare_segment_ignore_object_velocity_…
Browse files Browse the repository at this point in the history
…thresh (#8532)

change parameter name for more expressive name

Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 authored Aug 21, 2024
1 parent 1cb1863 commit 52c558d
Show file tree
Hide file tree
Showing 5 changed files with 13 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@
general_lanes: false
intersection: true
turns: true
prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
stopped_object_velocity_threshold: 1.0 # [m/s]
check_objects_on_current_lanes: true
check_objects_on_other_lanes: true
use_all_predicted_path: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ struct Parameters
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
bool enable_collision_check_for_prepare_phase_in_intersection{true};
bool enable_collision_check_for_prepare_phase_in_turns{true};
double prepare_segment_ignore_object_velocity_thresh{0.1};
double stopped_object_velocity_threshold{0.1};
bool check_objects_on_current_lanes{true};
bool check_objects_on_other_lanes{true};
bool use_all_predicted_path{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
p.enable_collision_check_for_prepare_phase_in_turns =
getOrDeclareParameter<bool>(*node, parameter("enable_collision_check_for_prepare_phase.turns"));
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
p.stopped_object_velocity_threshold =
getOrDeclareParameter<double>(*node, parameter("stopped_object_velocity_threshold"));
p.check_objects_on_current_lanes =
getOrDeclareParameter<bool>(*node, parameter("check_objects_on_current_lanes"));
p.check_objects_on_other_lanes =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ void NormalLaneChange::insertStopPoint(
for (const auto & object : target_objects.current_lane) {
// check if stationary
const auto obj_v = std::abs(object.initial_twist.twist.linear.x);
if (obj_v > lane_change_parameters_->stop_velocity_threshold) {
if (obj_v > lane_change_parameters_->stopped_object_velocity_threshold) {
continue;
}

Expand Down Expand Up @@ -476,7 +476,7 @@ void NormalLaneChange::insertStopPoint(
target_objects.target_lane_leading.begin(), target_objects.target_lane_leading.end(),
[&](const auto & o) {
const auto v = std::abs(o.initial_twist.twist.linear.x);
if (v > lane_change_parameters_->stop_velocity_threshold) {
if (v > lane_change_parameters_->stopped_object_velocity_threshold) {
return false;
}

Expand Down Expand Up @@ -1216,7 +1216,8 @@ FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets(
is_before_terminal()) {
const auto ahead_of_ego =
utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object);
constexpr double stopped_obj_vel_th = 1.0;
const auto stopped_obj_vel_th =
common_data_ptr_->lc_param_ptr->stopped_object_velocity_threshold;
if (object.kinematics.initial_twist_with_covariance.twist.linear.x < stopped_obj_vel_th) {
if (ahead_of_ego) {
target_lane_leading_objects.push_back(object);
Expand Down Expand Up @@ -2157,11 +2158,10 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj(
obj, lane_change_parameters_->use_all_predicted_path);
auto is_safe = true;
const auto selected_rss_param =
(obj.initial_twist.twist.linear.x <=
lane_change_parameters_->prepare_segment_ignore_object_velocity_thresh)
? lane_change_parameters_->rss_params_for_parked
: rss_params;
const auto selected_rss_param = (obj.initial_twist.twist.linear.x <=
lane_change_parameters_->stopped_object_velocity_threshold)
? lane_change_parameters_->rss_params_for_parked
: rss_params;
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, selected_rss_param, 1.0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1092,8 +1092,7 @@ ExtendedPredictedObject transform(

const auto & time_resolution = lane_change_parameters.prediction_time_resolution;
const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration;
const auto & velocity_threshold =
lane_change_parameters.prepare_segment_ignore_object_velocity_thresh;
const auto & velocity_threshold = lane_change_parameters.stopped_object_velocity_threshold;
const auto start_time = check_at_prepare_phase ? 0.0 : prepare_duration;
const double obj_vel_norm = std::hypot(
extended_object.initial_twist.twist.linear.x, extended_object.initial_twist.twist.linear.y);
Expand Down

0 comments on commit 52c558d

Please sign in to comment.