@@ -619,7 +619,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
619
619
Pose pose_zero;
620
620
pose_zero.position .x = 0 ;
621
621
pose_zero.position .y = 0 ;
622
- pose_zero.orientation = createQuaternionFromYaw (0 );
622
+ pose_zero.orientation = create_quaternion_from_yaw (0 );
623
623
const auto clothoid_min =
624
624
generateClothoidPath (R_E_far, L_min, pose_zero, arc_path_interval, true , true );
625
625
const auto q = clothoid_min.points .back ().point .pose ;
@@ -635,22 +635,22 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
635
635
636
636
const double mu_offset = (left_side_parking ^ is_forward) ? -mu : mu;
637
637
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 );
639
639
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);
642
642
643
643
const double self_yaw = tf2::getYaw (start_pose_dummy.orientation );
644
644
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);
646
646
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);
650
650
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);
652
652
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);
654
654
655
655
const double angle_offset =
656
656
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(
667
667
// combine road and shoulder lanes
668
668
// cut the road lanes up to start_pose to prevent unintended processing for overlapped lane
669
669
lanelet::ConstLanelets lanes{};
670
- autoware::universe_utils ::Point2d start_point2d (
670
+ autoware_utils ::Point2d start_point2d (
671
671
start_pose_dummy.position .x , start_pose_dummy.position .y );
672
672
for (const auto & lane : road_lanes) {
673
673
if (boost::geometry::within (start_point2d, lane.polygon2d ().basicPolygon ())) {
@@ -705,8 +705,8 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
705
705
}
706
706
707
707
// 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 );
710
710
const double alpha_tot_near = std::acos (
711
711
(std::pow (R_E_near, 2 ) + std::pow (R_E_near + R_1, 2 ) - std::pow (d_C_far_Einit, 2 )) /
712
712
(2 * R_E_near * (R_E_near + R_1)));
@@ -718,7 +718,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrialClothoid(
718
718
(left_side_parking ? -1.0 : 1.0 ) * R_1 * (1 - std::cos (alpha_tot_far));
719
719
const double inflection_yaw_offset =
720
720
(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 (
722
722
arc_end_pose_dummy, inflection_x_offset, inflection_y_offset, 0 , inflection_yaw_offset);
723
723
724
724
const auto generateClothoidalSequenceWithHeader =
@@ -1042,10 +1042,10 @@ PathWithLaneId GeometricParallelParking::generateClothoidPath(
1042
1042
Pose pose;
1043
1043
pose.position .x = x;
1044
1044
pose.position .y = y;
1045
- pose.orientation = createQuaternionFromYaw (yaw);
1045
+ pose.orientation = create_quaternion_from_yaw (yaw);
1046
1046
// get pose in map coords
1047
1047
PathPointWithLaneId p{};
1048
- p.point .pose = transformPose (pose, start_pose);
1048
+ p.point .pose = transform_pose (pose, start_pose);
1049
1049
return p;
1050
1050
};
1051
1051
0 commit comments