Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(behavior_path_planner): remove unnecessary functions #3271

Merged
merged 2 commits into from
Apr 5, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -102,10 +102,6 @@ void getProjectedDistancePointFromPolygons(
Pose & point_on_object);
// data conversions

std::vector<Pose> convertToPoseArray(const PathWithLaneId & path);

PoseArray convertToGeometryPoseArray(const PathWithLaneId & path);

PredictedPath convertToPredictedPath(
const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & pose,
const double nearest_seg_idx, const double duration, const double resolution,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@
#include <vector>

using autoware_auto_planning_msgs::msg::PathWithLaneId;
using behavior_path_planner::util::convertToGeometryPoseArray;
using behavior_path_planner::util::removeOverlappingPoints;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
Expand Down
22 changes: 0 additions & 22 deletions planning/behavior_path_planner/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,33 +122,11 @@ using geometry_msgs::msg::PoseWithCovarianceStamped;
using tf2::fromMsg;
using tier4_autoware_utils::Point2d;

std::vector<Pose> convertToPoseArray(const PathWithLaneId & path)
{
std::vector<Pose> pose_array;
pose_array.reserve(path.points.size());
for (const auto & pt : path.points) {
pose_array.push_back(pt.point.pose);
}
return pose_array;
}

double l2Norm(const Vector3 vector)
{
return std::sqrt(std::pow(vector.x, 2) + std::pow(vector.y, 2) + std::pow(vector.z, 2));
}

PoseArray convertToGeometryPoseArray(const PathWithLaneId & path)
{
PoseArray converted_array;
converted_array.header = path.header;

converted_array.poses.reserve(path.points.size());
for (const auto & point_with_id : path.points) {
converted_array.poses.push_back(point_with_id.point.pose);
}
return converted_array;
}

PredictedPath convertToPredictedPath(
const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & vehicle_pose,
const double nearest_seg_idx, const double duration, const double resolution,
Expand Down
12 changes: 4 additions & 8 deletions planning/behavior_path_planner/test/test_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,12 @@ TEST(BehaviorPathPlanningUtilitiesBehaviorTest, vehiclePoseToFrenetOnStraightLin
{
PathWithLaneId path =
behavior_path_planner::generateStraightSamplePathWithLaneId(0.0f, 1.0f, 10u);
std::vector<geometry_msgs::msg::Pose> geometry_points =
behavior_path_planner::util::convertToPoseArray(path);
Pose vehicle_pose = behavior_path_planner::generateEgoSamplePose(10.7f, -1.7f, 0.0);

const size_t vehicle_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
geometry_points, vehicle_pose, 3.0, 1.0);
path.points, vehicle_pose, 3.0, 1.0);
const auto vehicle_pose_frenet = behavior_path_planner::util::convertToFrenetPoint(
geometry_points, vehicle_pose.position, vehicle_seg_idx);
path.points, vehicle_pose.position, vehicle_seg_idx);

EXPECT_NEAR(vehicle_pose_frenet.distance, -1.7f, 1e-3);
EXPECT_NEAR(vehicle_pose_frenet.length, 10.7f, 1e-3);
Expand All @@ -46,14 +44,12 @@ TEST(BehaviorPathPlanningUtilitiesBehaviorTest, vehiclePoseToFrenetOnDiagonalLin
{
PathWithLaneId path =
behavior_path_planner::generateDiagonalSamplePathWithLaneId(0.0f, 1.0f, 10u);
std::vector<geometry_msgs::msg::Pose> geometry_points =
behavior_path_planner::util::convertToPoseArray(path);
Pose vehicle_pose = behavior_path_planner::generateEgoSamplePose(0.1f, 0.1f, 0.0);

const size_t vehicle_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
geometry_points, vehicle_pose, 3.0, 1.0);
path.points, vehicle_pose, 3.0, 1.0);
const auto vehicle_pose_frenet = behavior_path_planner::util::convertToFrenetPoint(
geometry_points, vehicle_pose.position, vehicle_seg_idx);
path.points, vehicle_pose.position, vehicle_seg_idx);

EXPECT_NEAR(vehicle_pose_frenet.distance, 0, 1e-2);
EXPECT_NEAR(vehicle_pose_frenet.length, 0.1414f, 1e-2);
Expand Down