Skip to content

Commit

Permalink
refactor(behavior_path_planner): use util function convertToPredicted…
Browse files Browse the repository at this point in the history
…Path from lane_change (autowarefoundation#5013)
  • Loading branch information
kyoichi-sugahara authored Sep 19, 2023
1 parent 8eeb11d commit f492916
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -160,9 +160,6 @@ std::vector<PoseWithVelocityStamped> convertToPredictedPath(
const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose,
const BehaviorPathPlannerParameters & common_parameters, const double resolution);

PredictedPath convertToPredictedPath(
const std::vector<PoseWithVelocityStamped> & path, const double time_resolution);

bool isParkedObject(
const PathWithLaneId & path, const RouteHandler & route_handler,
const ExtendedPredictedObject & object, const double object_check_min_road_shoulder_width,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1346,7 +1346,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
const auto ego_predicted_path = utils::lane_change::convertToPredictedPath(
lane_change_path, current_twist, current_pose, common_parameters, time_resolution);
const auto debug_predicted_path =
utils::lane_change::convertToPredictedPath(ego_predicted_path, time_resolution);
utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution);

auto collision_check_objects = target_objects.target_lane;

Expand Down
13 changes: 0 additions & 13 deletions planning/behavior_path_planner/src/utils/lane_change/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -829,19 +829,6 @@ std::vector<PoseWithVelocityStamped> convertToPredictedPath(
return predicted_path;
}

PredictedPath convertToPredictedPath(
const std::vector<PoseWithVelocityStamped> & path, const double time_resolution)
{
PredictedPath predicted_path;
predicted_path.time_step = rclcpp::Duration::from_seconds(time_resolution);
predicted_path.path.resize(path.size());

for (size_t i = 0; i < path.size(); ++i) {
predicted_path.path.at(i) = path.at(i).pose;
}
return predicted_path;
}

bool isParkedObject(
const PathWithLaneId & path, const RouteHandler & route_handler,
const ExtendedPredictedObject & object, const double object_check_min_road_shoulder_width,
Expand Down

0 comments on commit f492916

Please sign in to comment.