@@ -180,7 +180,7 @@ TEST(SmootherTest, test_simple_smoother)
180180 EXPECT_NEAR (straight_regular_path.poses [5 ].pose .position .x , 0.607 , 0.01 );
181181 EXPECT_NEAR (straight_regular_path.poses [5 ].pose .position .y , 0.387 , 0.01 );
182182
183- // Test that collisions are rejected
183+ // Test that collisions are disregarded
184184 nav_msgs::msg::Path collision_path;
185185 collision_path.poses .resize (11 );
186186 collision_path.poses [0 ].pose .position .x = 0.0 ;
@@ -205,7 +205,7 @@ TEST(SmootherTest, test_simple_smoother)
205205 collision_path.poses [9 ].pose .position .y = 1.4 ;
206206 collision_path.poses [10 ].pose .position .x = 1.5 ;
207207 collision_path.poses [10 ].pose .position .y = 1.5 ;
208- EXPECT_THROW (smoother->smooth (collision_path, max_time), nav2_core::FailedToSmoothPath );
208+ EXPECT_TRUE (smoother->smooth (collision_path, max_time));
209209
210210 // test cusp / reversing segments
211211 nav_msgs::msg::Path reversing_path;
@@ -232,7 +232,7 @@ TEST(SmootherTest, test_simple_smoother)
232232 reversing_path.poses [9 ].pose .position .y = 0.1 ;
233233 reversing_path.poses [10 ].pose .position .x = 0.5 ;
234234 reversing_path.poses [10 ].pose .position .y = 0.0 ;
235- EXPECT_THROW (smoother->smooth (reversing_path, max_time), nav2_core::FailedToSmoothPath );
235+ EXPECT_TRUE (smoother->smooth (reversing_path, max_time));
236236
237237 // test rotate in place
238238 tf2::Quaternion quat1, quat2;
@@ -244,7 +244,18 @@ TEST(SmootherTest, test_simple_smoother)
244244 straight_irregular_path.poses [6 ].pose .position .x = 0.5 ;
245245 straight_irregular_path.poses [6 ].pose .position .y = 0.5 ;
246246 straight_irregular_path.poses [6 ].pose .orientation = tf2::toMsg (quat2);
247- EXPECT_THROW (smoother->smooth (straight_irregular_path, max_time), nav2_core::FailedToSmoothPath);
247+ EXPECT_TRUE (smoother->smooth (straight_irregular_path, max_time));
248+
249+ // test approach
250+ nav_msgs::msg::Path approach_path;
251+ approach_path.poses .resize (3 );
252+ approach_path.poses [0 ].pose .position .x = 0.5 ;
253+ approach_path.poses [0 ].pose .position .y = 0.0 ;
254+ approach_path.poses [1 ].pose .position .x = 0.5 ;
255+ approach_path.poses [1 ].pose .position .y = 0.1 ;
256+ approach_path.poses [2 ].pose .position .x = 0.5 ;
257+ approach_path.poses [2 ].pose .position .y = 0.2 ;
258+ EXPECT_TRUE (smoother->smooth (approach_path, max_time));
248259
249260 // test max iterations
250261 smoother->setMaxItsToInvalid ();
@@ -272,5 +283,5 @@ TEST(SmootherTest, test_simple_smoother)
272283 max_its_path.poses [9 ].pose .position .y = 0.9 ;
273284 max_its_path.poses [10 ].pose .position .x = 0.5 ;
274285 max_its_path.poses [10 ].pose .position .y = 1.0 ;
275- EXPECT_THROW (smoother->smooth (max_its_path, max_time), nav2_core::FailedToSmoothPath );
286+ EXPECT_TRUE (smoother->smooth (max_its_path, max_time));
276287}
0 commit comments