Skip to content

Commit

Permalink
modify some inconsistency
Browse files Browse the repository at this point in the history
Signed-off-by: Takumi Ito <takumi.ito@tier4.jp>
  • Loading branch information
Takumi Ito committed Jan 29, 2025
1 parent 19ec1be commit 69e1271
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@
forward_parking_velocity: 1.38
forward_parking_lane_departure_margin: 0.0
forward_parking_path_interval: 1.0
forward_parking_max_steer_angle: 0.35 # 20deg
forward_parking_max_steer_angle: 0.4 # 22.9deg
forward_parking_steer_rate_lim: 0.35
forward_parking_use_clothoid: true
backward:
Expand All @@ -90,7 +90,7 @@
backward_parking_velocity: -1.38
backward_parking_lane_departure_margin: 0.0
backward_parking_path_interval: 1.0
backward_parking_max_steer_angle: 0.35 # 20deg
backward_parking_max_steer_angle: 0.4 # 22.9deg
backward_parking_steer_rate_lim: 0.35
backward_parking_use_clothoid: true

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters(
p.parallel_parking_parameters.forward_parking_max_steer_angle =
node->declare_parameter<double>(ns + "forward_parking_max_steer_angle"); // 20deg
p.parallel_parking_parameters.forward_parking_steer_rate_lim =
node->declare_parameter<double>(ns + "forward_parking_steer_rate_lim"); // 20deg
node->declare_parameter<double>(ns + "forward_parking_steer_rate_lim");
p.parallel_parking_parameters.forward_parking_use_clothoid =
node->declare_parameter<bool>(ns + "forward_parking_use_clothoid");
}
Expand All @@ -207,7 +207,7 @@ GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters(
p.parallel_parking_parameters.backward_parking_max_steer_angle =
node->declare_parameter<double>(ns + "backward_parking_max_steer_angle"); // 20deg
p.parallel_parking_parameters.backward_parking_steer_rate_lim =
node->declare_parameter<double>(ns + "backward_parking_steer_rate_lim"); // 20deg
node->declare_parameter<double>(ns + "backward_parking_steer_rate_lim");
p.parallel_parking_parameters.backward_parking_use_clothoid =
node->declare_parameter<bool>(ns + "backward_parking_use_clothoid");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,9 +82,6 @@ std::optional<PullOverPath> GeometricPullOver::plan(
auto pull_over_path_opt = PullOverPath::create(
getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose,
planner_.getPairsTerminalVelocityAndAccel());
if (!pull_over_path_opt) {
return {};
}
return pull_over_path_opt.value();
return pull_over_path_opt;
}
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,7 @@ bool GeometricParallelParking::planPullOver(
}
}
}

return false;
}

Expand Down

0 comments on commit 69e1271

Please sign in to comment.