Skip to content

Commit a5f5245

Browse files
adding parameter
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 32bd7e2 commit a5f5245

File tree

4 files changed

+10
-2
lines changed

4 files changed

+10
-2
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,10 @@
3030
min_road_shoulder_width: 0.5 # [m]
3131
th_parked_vehicle_shift_ratio: 0.6
3232

33+
# trajectory generation near terminal using frenet planner
34+
frenet:
35+
enable: true
36+
3337
# safety check
3438
safety_check:
3539
allow_loose_check_for_cancel: true

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,6 @@ struct TrajectoryParameters
132132
int lon_acc_sampling_num{10};
133133
int lat_acc_sampling_num{10};
134134
LateralAccelerationMap lat_acc_map{};
135-
FrenetPlannerParameters frenet{};
136135
};
137136

138137
struct DelayParameters
@@ -149,6 +148,7 @@ struct Parameters
149148
SafetyParameters safety{};
150149
CancelParameters cancel{};
151150
DelayParameters delay{};
151+
FrenetPlannerParameters frenet{};
152152

153153
// lane change parameters
154154
double backward_lane_length{200.0};

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -211,6 +211,10 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s
211211
p.delay.th_parked_vehicle_shift_ratio = getOrDeclareParameter<double>(
212212
*node, parameter("delay_lane_change.th_parked_vehicle_shift_ratio"));
213213

214+
// trajectory generation near terminal using frenet planner
215+
p.frenet.enable =
216+
getOrDeclareParameter<bool>(*node, parameter("frenet.enable"));
217+
214218
// lane change cancel
215219
p.cancel.enable_on_prepare_phase =
216220
getOrDeclareParameter<bool>(*node, parameter("cancel.enable_on_prepare_phase"));

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1101,7 +1101,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths)
11011101
const auto prepare_phase_metrics = get_prepare_metrics();
11021102

11031103
if (
1104-
common_data_ptr_->lc_param_ptr->trajectory.frenet.enable &&
1104+
common_data_ptr_->lc_param_ptr->frenet.enable &&
11051105
common_data_ptr_->transient_data.is_ego_near_current_terminal_start) {
11061106
return get_path_using_frenet(prepare_phase_metrics, target_objects, candidate_paths);
11071107
}

0 commit comments

Comments
 (0)