@@ -49,10 +49,11 @@ TEST_F(TestRouteHandler, getGoalLaneId)
49
49
50
50
TEST_F (TestRouteHandler, getLaneletSequenceWhenOverlappingRoute)
51
51
{
52
- set_route_handler (" /test_map/ overlap_map.osm" );
52
+ set_route_handler (" overlap_map.osm" );
53
53
ASSERT_FALSE (route_handler_->isHandlerReady ());
54
54
55
- geometry_msgs::msg::Pose start_pose, goal_pose;
55
+ geometry_msgs::msg::Pose start_pose;
56
+ geometry_msgs::msg::Pose goal_pose;
56
57
start_pose.position = autoware::universe_utils::createPoint (3728.870361 , 73739.281250 , 0 );
57
58
start_pose.orientation = autoware::universe_utils::createQuaternion (0 , 0 , -0.513117 , 0.858319 );
58
59
goal_pose.position = autoware::universe_utils::createPoint (3729.961182 , 73727.328125 , 0 );
@@ -79,11 +80,12 @@ TEST_F(TestRouteHandler, getLaneletSequenceWhenOverlappingRoute)
79
80
80
81
TEST_F (TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute)
81
82
{
82
- set_route_handler (" /test_map/ overlap_map.osm" );
83
- set_test_route (" /test_route/ overlap_test_route.yaml" );
83
+ set_route_handler (" overlap_map.osm" );
84
+ set_test_route (" overlap_test_route.yaml" );
84
85
ASSERT_TRUE (route_handler_->isHandlerReady ());
85
86
86
- geometry_msgs::msg::Pose reference_pose, search_pose;
87
+ geometry_msgs::msg::Pose reference_pose;
88
+ geometry_msgs::msg::Pose search_pose;
87
89
88
90
lanelet::ConstLanelet reference_lanelet;
89
91
reference_pose.position = autoware::universe_utils::createPoint (3730.88 , 73735.3 , 0 );
@@ -102,71 +104,189 @@ TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute)
102
104
ASSERT_EQ (closest_lanelet.id (), 345 );
103
105
104
106
found_lanelet = route_handler_->getClosestRouteLaneletFromLanelet (
105
- search_pose, reference_lanelet, &closest_lanelet, 3.0 , 1.046 );
107
+ search_pose, reference_lanelet, &closest_lanelet, dist_threshold, yaw_threshold );
106
108
ASSERT_TRUE (found_lanelet);
107
109
ASSERT_EQ (closest_lanelet.id (), 277 );
108
110
}
109
111
110
- // TEST_F(TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute)
111
- // {
112
- // lanelet::ConstLanelet closest_lane;
113
-
114
- // Pose search_pose;
115
-
116
- // search_pose.position = autoware::universe_utils::createPoint(-1.0, 1.75, 0);
117
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
118
- // const auto closest_lane_obtained7 =
119
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
120
-
121
- // ASSERT_TRUE(closest_lane_obtained7);
122
- // ASSERT_EQ(closest_lane.id(), 4775);
123
-
124
- // search_pose.position = autoware::universe_utils::createPoint(-0.5, 1.75, 0);
125
- // const auto closest_lane_obtained =
126
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
127
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
128
-
129
- // ASSERT_TRUE(closest_lane_obtained);
130
- // ASSERT_EQ(closest_lane.id(), 4775);
131
-
132
- // search_pose.position = autoware::universe_utils::createPoint(-.01, 1.75, 0);
133
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
134
- // const auto closest_lane_obtained3 =
135
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
112
+ TEST_F (TestRouteHandler, CheckLaneIsInGoalRouteSection)
113
+ {
114
+ const auto lane = route_handler_->getLaneletsFromId (4785 );
115
+ const auto is_lane_in_goal_route_section = route_handler_->isInGoalRouteSection (lane);
116
+ ASSERT_TRUE (is_lane_in_goal_route_section);
117
+ }
136
118
137
- // ASSERT_TRUE(closest_lane_obtained3);
138
- // ASSERT_EQ(closest_lane.id(), 4775);
119
+ TEST_F (TestRouteHandler, CheckLaneIsNotInGoalRouteSection)
120
+ {
121
+ const auto lane = route_handler_->getLaneletsFromId (4780 );
122
+ const auto is_lane_in_goal_route_section = route_handler_->isInGoalRouteSection (lane);
123
+ ASSERT_FALSE (is_lane_in_goal_route_section);
124
+ }
139
125
140
- // search_pose.position = autoware::universe_utils::createPoint(0.0, 1.75, 0);
141
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
142
- // const auto closest_lane_obtained1 =
143
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
126
+ TEST_F (TestRouteHandler, checkGetLaneletSequence)
127
+ {
128
+ const auto current_pose = autoware::test_utils::createPose (-50.0 , 1.75 , 0.0 , 0.0 , 0.0 , 0.0 );
144
129
145
- // ASSERT_TRUE(closest_lane_obtained1);
146
- // ASSERT_EQ(closest_lane.id(), 4775);
130
+ lanelet::ConstLanelet closest_lanelet;
131
+ const auto found_closest_lanelet = route_handler_->getClosestLaneletWithConstrainsWithinRoute (
132
+ current_pose, &closest_lanelet, dist_threshold, yaw_threshold);
133
+ ASSERT_TRUE (found_closest_lanelet);
134
+ ASSERT_EQ (closest_lanelet.id (), 4765ul );
135
+
136
+ const auto current_lanes = route_handler_->getLaneletSequence (
137
+ closest_lanelet, current_pose, backward_path_length, forward_path_length);
138
+
139
+ ASSERT_EQ (current_lanes.size (), 6ul );
140
+ ASSERT_EQ (current_lanes.at (0 ).id (), 4765ul );
141
+ ASSERT_EQ (current_lanes.at (1 ).id (), 4770ul );
142
+ ASSERT_EQ (current_lanes.at (2 ).id (), 4775ul );
143
+ ASSERT_EQ (current_lanes.at (3 ).id (), 4424ul );
144
+ ASSERT_EQ (current_lanes.at (4 ).id (), 4780ul );
145
+ ASSERT_EQ (current_lanes.at (5 ).id (), 4785ul );
146
+ }
147
147
148
- // search_pose.position = autoware::universe_utils::createPoint(0.01, 1.75, 0);
149
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
150
- // const auto closest_lane_obtained2 =
151
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
148
+ TEST_F (TestRouteHandler, checkLateralIntervalToPreferredLaneWhenLaneChangeToRight)
149
+ {
150
+ const auto current_lanes = get_current_lanes ();
151
+
152
+ // The input is within expectation.
153
+ // this lane is of preferred lane type
154
+ std::for_each (current_lanes.begin (), current_lanes.begin () + 3 , [&](const auto & lane) {
155
+ const auto result = route_handler_->getLateralIntervalsToPreferredLane (lane, Direction::RIGHT);
156
+ ASSERT_EQ (result.size (), 0ul );
157
+ });
158
+
159
+ // The input is within expectation.
160
+ // this alternative lane is a subset of preferred lane route section
161
+ std::for_each (current_lanes.begin () + 3 , current_lanes.end (), [&](const auto & lane) {
162
+ const auto result = route_handler_->getLateralIntervalsToPreferredLane (lane, Direction::RIGHT);
163
+ ASSERT_EQ (result.size (), 1ul );
164
+ EXPECT_DOUBLE_EQ (result.at (0 ), -3.5 );
165
+ });
166
+
167
+ // The input is within expectation.
168
+ // Although Direction::NONE, the function should still return result similar to
169
+ // Direction::RIGHT.
170
+ std::for_each (current_lanes.begin (), current_lanes.begin () + 3 , [&](const auto & lane) {
171
+ const auto result = route_handler_->getLateralIntervalsToPreferredLane (lane, Direction::NONE);
172
+ ASSERT_EQ (result.size (), 0ul );
173
+ });
174
+
175
+ // The input is within expectation.
176
+ // Although Direction::NONE is provided, the function should behave similarly to
177
+ // Direction::RIGHT.
178
+ std::for_each (current_lanes.begin () + 3 , current_lanes.end (), [&](const auto & lane) {
179
+ const auto result = route_handler_->getLateralIntervalsToPreferredLane (lane, Direction::NONE);
180
+ ASSERT_EQ (result.size (), 1ul );
181
+ EXPECT_DOUBLE_EQ (result.at (0 ), -3.5 );
182
+ });
183
+ }
152
184
153
- // ASSERT_TRUE(closest_lane_obtained2);
154
- // ASSERT_EQ(closest_lane.id(), 4424);
185
+ TEST_F (TestRouteHandler, checkLateralIntervalToPreferredLaneUsingUnexpectedResults)
186
+ {
187
+ const auto current_lanes = get_current_lanes ();
155
188
156
- // search_pose.position = autoware::universe_utils::createPoint(0.5, 1.75, 0);
157
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
158
- // const auto closest_lane_obtained4 =
159
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
189
+ std::for_each (current_lanes.begin (), current_lanes.end (), [&](const auto & lane) {
190
+ const auto result = route_handler_->getLateralIntervalsToPreferredLane (lane, Direction::LEFT);
191
+ ASSERT_EQ (result.size (), 0ul );
192
+ });
193
+ }
160
194
161
- // ASSERT_TRUE(closest_lane_obtained4);
162
- // ASSERT_EQ(closest_lane.id(), 4424);
195
+ TEST_F (TestRouteHandler, testGetCenterLinePath)
196
+ {
197
+ const auto current_lanes = route_handler_->getLaneletsFromIds ({4424 , 4780 , 4785 });
198
+ {
199
+ // The input is within expectation.
200
+ const auto center_line_path = route_handler_->getCenterLinePath (current_lanes, 0.0 , 50.0 );
201
+ ASSERT_EQ (center_line_path.points .size (), 51 ); // 26 + 26 - 1(overlapped)
202
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .size (), 2 );
203
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .at (0 ), 4780 );
204
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .at (1 ), 4785 );
205
+ }
206
+ {
207
+ // The input is broken.
208
+ // s_start is negative, and s_end is over the boundary.
209
+ const auto center_line_path = route_handler_->getCenterLinePath (current_lanes, -1.0 , 200.0 );
210
+ ASSERT_EQ (center_line_path.points .size (), 76 ); // 26 + 26 + 26 - 2(overlapped)
211
+ ASSERT_EQ (center_line_path.points .front ().lane_ids .size (), 1 );
212
+ ASSERT_EQ (center_line_path.points .front ().lane_ids .at (0 ), 4424 );
213
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .size (), 1 );
214
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .at (0 ), 4785 );
215
+ }
216
+ }
217
+ TEST_F (TestRouteHandler, DISABLED_testGetCenterLinePathWhenLanesIsNotConnected)
218
+ {
219
+ // broken current lanes. 4424 and 4785 are not connected directly.
220
+ const auto current_lanes = route_handler_->getLaneletsFromIds ({4424 , 4780 , 4785 });
221
+
222
+ // The input is broken. Test is disabled because it doesn't pass.
223
+ const auto center_line_path = route_handler_->getCenterLinePath (current_lanes, 0.0 , 75.0 );
224
+ ASSERT_EQ (center_line_path.points .size (), 26 ); // 26 + 26 + 26 - 2(overlapped)
225
+ ASSERT_EQ (center_line_path.points .front ().lane_ids .size (), 1 );
226
+ ASSERT_EQ (center_line_path.points .front ().lane_ids .at (0 ), 4424 );
227
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .size (), 1 );
228
+ ASSERT_EQ (center_line_path.points .back ().lane_ids .at (0 ), 4424 );
229
+ }
163
230
164
- // search_pose.position = autoware::universe_utils::createPoint(1.0, 1.75, 0);
165
- // search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0);
166
- // const auto closest_lane_obtained5 =
167
- // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane);
231
+ TEST_F (TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute)
232
+ {
233
+ auto get_closest_lanelet_within_route =
234
+ [&](double x, double y, double z) -> std::optional<lanelet::Id> {
235
+ const auto pose = autoware::test_utils::createPose (x, y, z, 0.0 , 0.0 , 0.0 );
236
+ lanelet::ConstLanelet closest_lanelet;
237
+ const auto closest_lane_obtained =
238
+ route_handler_->getClosestLaneletWithinRoute (pose, &closest_lanelet);
239
+ if (!closest_lane_obtained) {
240
+ return std::nullopt;
241
+ }
242
+ return closest_lanelet.id ();
243
+ };
244
+
245
+ ASSERT_TRUE (get_closest_lanelet_within_route (-0.5 , 1.75 , 0 ).has_value ());
246
+ ASSERT_EQ (get_closest_lanelet_within_route (-0.5 , 1.75 , 0 ).value (), 4775ul );
247
+
248
+ ASSERT_TRUE (get_closest_lanelet_within_route (-0.01 , 1.75 , 0 ).has_value ());
249
+ ASSERT_EQ (get_closest_lanelet_within_route (-0.01 , 1.75 , 0 ).value (), 4775ul );
250
+
251
+ ASSERT_TRUE (get_closest_lanelet_within_route (0.0 , 1.75 , 0 ).has_value ());
252
+ ASSERT_EQ (get_closest_lanelet_within_route (0.0 , 1.75 , 0 ).value (), 4775ul );
253
+
254
+ ASSERT_TRUE (get_closest_lanelet_within_route (0.01 , 1.75 , 0 ).has_value ());
255
+ ASSERT_EQ (get_closest_lanelet_within_route (0.01 , 1.75 , 0 ).value (), 4424ul );
256
+
257
+ ASSERT_TRUE (get_closest_lanelet_within_route (0.5 , 1.75 , 0 ).has_value ());
258
+ ASSERT_EQ (get_closest_lanelet_within_route (0.5 , 1.75 , 0 ).value (), 4424ul );
259
+ }
168
260
169
- // ASSERT_TRUE(closest_lane_obtained5);
170
- // ASSERT_EQ(closest_lane.id(), 4424);
171
- // }
261
+ TEST_F (TestRouteHandler, testGetLaneChangeTargetLanes)
262
+ {
263
+ {
264
+ // The input is within expectation.
265
+ // There exist no lane changing lane since both 4770 and 4775 are preferred lane.
266
+ const auto current_lanes = route_handler_->getLaneletsFromIds ({4770 , 4775 });
267
+ const auto lane_change_lane =
268
+ route_handler_->getLaneChangeTarget (current_lanes, Direction::RIGHT);
269
+ ASSERT_FALSE (lane_change_lane.has_value ());
270
+ }
271
+
272
+ {
273
+ // The input is within expectation.
274
+ // There exist lane changing lane since 4424 is subset of preferred lane 9598.
275
+ const auto current_lanes = route_handler_->getLaneletsFromIds ({4775 , 4424 });
276
+ const auto lane_change_lane =
277
+ route_handler_->getLaneChangeTarget (current_lanes, Direction::RIGHT);
278
+ EXPECT_TRUE (lane_change_lane.has_value ());
279
+ ASSERT_EQ (lane_change_lane.value ().id (), 9598ul );
280
+ }
281
+
282
+ {
283
+ // The input is within expectation.
284
+ // There is a lane-changing lane. Within the maximum current lanes, there is an alternative lane
285
+ // to the preferred lane. Therefore, the lane-changing lane exists.
286
+ const auto current_lanes = get_current_lanes ();
287
+ const auto lane_change_lane = route_handler_->getLaneChangeTarget (current_lanes);
288
+ ASSERT_TRUE (lane_change_lane.has_value ());
289
+ ASSERT_EQ (lane_change_lane.value ().id (), 9598ul );
290
+ }
291
+ }
172
292
} // namespace autoware::route_handler::test
0 commit comments