@@ -99,22 +99,37 @@ void getProjectedDistancePointFromPolygons(
99
99
100
100
Path convertToPathFromPathWithLaneId (const PathWithLaneId & path_with_lane_id);
101
101
102
- std::vector<Point > convertToPointArray (const PathWithLaneId & path);
102
+ std::vector<Pose> convertToPoseArray (const PathWithLaneId & path);
103
103
104
104
std::vector<Point > convertToGeometryPointArray (const PathWithLaneId & path);
105
105
106
106
PoseArray convertToGeometryPoseArray (const PathWithLaneId & path);
107
107
108
108
PredictedPath convertToPredictedPath (
109
- const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & vehicle_pose ,
110
- const double duration , const double resolution , const double acceleration ,
111
- double min_speed = 1.0 );
109
+ const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & pose ,
110
+ const double nearest_seg_idx , const double duration , const double resolution ,
111
+ const double acceleration, const double min_speed = 1.0 );
112
112
113
+ template <class T >
113
114
FrenetCoordinate3d convertToFrenetCoordinate3d (
114
- const std::vector<Point > & linestring, const Point & search_point_geom);
115
+ const std::vector<T> & pose_array, const Point & search_point_geom, const size_t seg_idx)
116
+ {
117
+ FrenetCoordinate3d frenet_coordinate;
115
118
116
- FrenetCoordinate3d convertToFrenetCoordinate3d (
117
- const PathWithLaneId & path, const Point & search_point_geom);
119
+ const double longitudinal_length =
120
+ motion_utils::calcLongitudinalOffsetToSegment (pose_array, seg_idx, search_point_geom);
121
+ frenet_coordinate.length =
122
+ motion_utils::calcSignedArcLength (pose_array, 0 , seg_idx) + longitudinal_length;
123
+ frenet_coordinate.distance = motion_utils::calcLateralOffset (pose_array, search_point_geom);
124
+
125
+ return frenet_coordinate;
126
+ }
127
+
128
+ inline FrenetCoordinate3d convertToFrenetCoordinate3d (
129
+ const PathWithLaneId & path, const Point & search_point_geom, const size_t seg_idx)
130
+ {
131
+ return convertToFrenetCoordinate3d (path.points , search_point_geom, seg_idx);
132
+ }
118
133
119
134
std::vector<uint64_t > getIds (const lanelet::ConstLanelets & lanelets);
120
135
@@ -142,7 +157,42 @@ double getArcLengthToTargetLanelet(
142
157
143
158
Pose lerpByPose (const Pose & p1, const Pose & p2, const double t);
144
159
145
- Point lerpByLength (const std::vector<Point > & array, const double length);
160
+ inline Point lerpByPoint (const Point & p1, const Point & p2, const double t)
161
+ {
162
+ tf2::Vector3 v1, v2;
163
+ v1.setValue (p1.x , p1.y , p1.z );
164
+ v2.setValue (p2.x , p2.y , p2.z );
165
+
166
+ const auto lerped_point = v1.lerp (v2, t);
167
+
168
+ Point point;
169
+ point.x = lerped_point.x ();
170
+ point.y = lerped_point.y ();
171
+ point.z = lerped_point.z ();
172
+ return point;
173
+ }
174
+
175
+ template <class T >
176
+ Point lerpByLength (const std::vector<T> & point_array, const double length)
177
+ {
178
+ Point lerped_point;
179
+ if (point_array.empty ()) {
180
+ return lerped_point;
181
+ }
182
+ Point prev_geom_pt = tier4_autoware_utils::getPoint (point_array.front ());
183
+ double accumulated_length = 0 ;
184
+ for (const auto & pt : point_array) {
185
+ const auto & geom_pt = tier4_autoware_utils::getPoint (pt);
186
+ const double distance = tier4_autoware_utils::calcDistance3d (prev_geom_pt, geom_pt);
187
+ if (accumulated_length + distance > length) {
188
+ return lerpByPoint (prev_geom_pt, geom_pt, (length - accumulated_length) / distance);
189
+ }
190
+ accumulated_length += distance;
191
+ prev_geom_pt = geom_pt;
192
+ }
193
+
194
+ return tier4_autoware_utils::getPoint (point_array.back ());
195
+ }
146
196
147
197
bool lerpByTimeStamp (const PredictedPath & path, const double t, Pose * lerped_pt);
148
198
0 commit comments