Skip to content

Commit eaf4610

Browse files
author
Takumi Ito
committed
modify inconsistency
Signed-off-by: Takumi Ito <takumi.ito@tier4.jp>
1 parent 6a7ed23 commit eaf4610

File tree

1 file changed

+16
-16
lines changed

1 file changed

+16
-16
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp

+16-16
Original file line numberDiff line numberDiff line change
@@ -619,7 +619,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
619619
Pose pose_zero;
620620
pose_zero.position.x = 0;
621621
pose_zero.position.y = 0;
622-
pose_zero.orientation = createQuaternionFromYaw(0);
622+
pose_zero.orientation = create_quaternion_from_yaw(0);
623623
const auto clothoid_min =
624624
generateClothoidPath(R_E_far, L_min, pose_zero, arc_path_interval, true, true);
625625
const auto q = clothoid_min.points.back().point.pose;
@@ -635,22 +635,22 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
635635

636636
const double mu_offset = (left_side_parking ^ is_forward) ? -mu : mu;
637637

638-
const Pose arc_end_pose = calcOffsetPose(goal_pose, end_pose_offset, 0, 0);
638+
const Pose arc_end_pose = calc_offset_pose(goal_pose, end_pose_offset, 0, 0);
639639

640-
const Pose start_pose_dummy = calcOffsetPose(start_pose, 0, 0, 0, mu_offset);
641-
const Pose arc_end_pose_dummy = calcOffsetPose(arc_end_pose, 0, 0, 0, mu_offset);
640+
const Pose start_pose_dummy = calc_offset_pose(start_pose, 0, 0, 0, mu_offset);
641+
const Pose arc_end_pose_dummy = calc_offset_pose(arc_end_pose, 0, 0, 0, mu_offset);
642642

643643
const double self_yaw = tf2::getYaw(start_pose_dummy.orientation);
644644
const double goal_yaw = tf2::getYaw(arc_end_pose_dummy.orientation);
645-
const double psi = normalizeRadian(self_yaw - goal_yaw);
645+
const double psi = normalize_radian(self_yaw - goal_yaw);
646646

647-
const Pose C_far = left_side_parking ? calcOffsetPose(arc_end_pose_dummy, 0, -R_1, 0)
648-
: calcOffsetPose(arc_end_pose_dummy, 0, R_1, 0);
649-
const double d_C_far_Einit = calcDistance2d(C_far, start_pose_dummy);
647+
const Pose C_far = left_side_parking ? calc_offset_pose(arc_end_pose_dummy, 0, -R_1, 0)
648+
: calc_offset_pose(arc_end_pose_dummy, 0, R_1, 0);
649+
const double d_C_far_Einit = calc_distance2d(C_far, start_pose_dummy);
650650

651-
const Point C_far_goal_coords = inverseTransformPoint(C_far.position, arc_end_pose_dummy);
651+
const Point C_far_goal_coords = inverse_transform_point(C_far.position, arc_end_pose_dummy);
652652
const Point self_point_goal_coords =
653-
inverseTransformPoint(start_pose_dummy.position, arc_end_pose_dummy);
653+
inverse_transform_point(start_pose_dummy.position, arc_end_pose_dummy);
654654

655655
const double angle_offset =
656656
std::asin((self_point_goal_coords.y - C_far_goal_coords.y) / d_C_far_Einit);
@@ -667,7 +667,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
667667
// combine road and shoulder lanes
668668
// cut the road lanes up to start_pose to prevent unintended processing for overlapped lane
669669
lanelet::ConstLanelets lanes{};
670-
autoware::universe_utils::Point2d start_point2d(
670+
autoware_utils::Point2d start_point2d(
671671
start_pose_dummy.position.x, start_pose_dummy.position.y);
672672
for (const auto & lane : road_lanes) {
673673
if (boost::geometry::within(start_point2d, lane.polygon2d().basicPolygon())) {
@@ -705,8 +705,8 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
705705
}
706706

707707
// Generate arc path(first turn -> second turn)
708-
const Pose C_near = left_side_parking ? calcOffsetPose(start_pose_dummy, 0, R_E_near, 0, 0)
709-
: calcOffsetPose(start_pose_dummy, 0, -R_E_near, 0, 0);
708+
const Pose C_near = left_side_parking ? calc_offset_pose(start_pose_dummy, 0, R_E_near, 0, 0)
709+
: calc_offset_pose(start_pose_dummy, 0, -R_E_near, 0, 0);
710710
const double alpha_tot_near = std::acos(
711711
(std::pow(R_E_near, 2) + std::pow(R_E_near + R_1, 2) - std::pow(d_C_far_Einit, 2)) /
712712
(2 * R_E_near * (R_E_near + R_1)));
@@ -718,7 +718,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
718718
(left_side_parking ? -1.0 : 1.0) * R_1 * (1 - std::cos(alpha_tot_far));
719719
const double inflection_yaw_offset =
720720
(is_forward ^ left_side_parking ? -1.0 : 1.0) * alpha_tot_far + mu_offset;
721-
const Pose inflection_point = calcOffsetPose(
721+
const Pose inflection_point = calc_offset_pose(
722722
arc_end_pose_dummy, inflection_x_offset, inflection_y_offset, 0, inflection_yaw_offset);
723723

724724
const auto generateClothoidalSequenceWithHeader =
@@ -1042,10 +1042,10 @@ PathWithLaneId GeometricParallelParking::generateClothoidPath(
10421042
Pose pose;
10431043
pose.position.x = x;
10441044
pose.position.y = y;
1045-
pose.orientation = createQuaternionFromYaw(yaw);
1045+
pose.orientation = create_quaternion_from_yaw(yaw);
10461046
// get pose in map coords
10471047
PathPointWithLaneId p{};
1048-
p.point.pose = transformPose(pose, start_pose);
1048+
p.point.pose = transform_pose(pose, start_pose);
10491049
return p;
10501050
};
10511051

0 commit comments

Comments
 (0)