Skip to content

Commit

Permalink
fix(start_planner): redefine the necessary parameters (#7477)
Browse files Browse the repository at this point in the history
* add necessary parameter which removed in previous PR mistakenly

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* change variable name

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

---------

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kyoichi-sugahara authored Jun 13, 2024
1 parent be75f1b commit 5b611e7
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ struct ParallelParkingParameters
// pull_out
double pull_out_velocity{0.0};
double pull_out_lane_departure_margin{0.0};
double pull_out_path_interval{0.0};
double pull_out_arc_path_interval{0.0};
double pull_out_max_steer_angle{0.0};
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,7 @@ bool GeometricParallelParking::planPullOut(
auto arc_paths = planOneTrial(
*end_pose, start_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_start,
start_pose_offset, parameters_.pull_out_lane_departure_margin,
parameters_.pull_out_path_interval, lane_departure_checker);
parameters_.pull_out_arc_path_interval, lane_departure_checker);
if (arc_paths.empty()) {
// not found path
continue;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
# geometric pull out
enable_geometric_pull_out: true
geometric_collision_check_distance_from_end: 0.0
arc_path_interval: 1.0
divide_pull_out_path: true
geometric_pull_out_velocity: 1.0
lane_departure_margin: 0.2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
p.divide_pull_out_path = node->declare_parameter<bool>(ns + "divide_pull_out_path");
p.parallel_parking_parameters.pull_out_velocity =
node->declare_parameter<double>(ns + "geometric_pull_out_velocity");
p.parallel_parking_parameters.pull_out_arc_path_interval =
node->declare_parameter<double>(ns + "arc_path_interval");
p.parallel_parking_parameters.pull_out_lane_departure_margin =
node->declare_parameter<double>(ns + "lane_departure_margin");
p.lane_departure_check_expansion_margin =
Expand Down Expand Up @@ -416,6 +418,9 @@ void StartPlannerModuleManager::updateModuleParams(
parameters, ns + "maximum_longitudinal_deviation", p->maximum_longitudinal_deviation);
updateParam<bool>(parameters, ns + "enable_geometric_pull_out", p->enable_geometric_pull_out);
updateParam<bool>(parameters, ns + "divide_pull_out_path", p->divide_pull_out_path);
updateParam<double>(
parameters, ns + "arc_path_interval",
p->parallel_parking_parameters.pull_out_arc_path_interval);
updateParam<double>(
parameters, ns + "lane_departure_margin",
p->parallel_parking_parameters.pull_out_lane_departure_margin);
Expand Down

0 comments on commit 5b611e7

Please sign in to comment.