2020#include < utility>
2121#include < vector>
2222
23- #include " nav2_core/planner_exceptions .hpp"
23+ #include " nav2_core/smoother_exceptions .hpp"
2424#include " nav2_smoother/nav2_smoother.hpp"
2525#include " nav2_util/node_utils.hpp"
2626#include " nav_2d_utils/conversions.hpp"
@@ -263,13 +263,17 @@ void SmootherServer::smoothPlan()
263263 if (findSmootherId (c_name, current_smoother)) {
264264 current_smoother_ = current_smoother;
265265 } else {
266- action_server_->terminate_current ();
267- return ;
266+ throw nav2_core::InvalidSmoother (" Invalid Smoother: " + c_name);
268267 }
269268
270269 // Perform smoothing
271270 auto goal = action_server_->get_current_goal ();
272271 result->path = goal->path ;
272+
273+ if (!validate (result->path )) {
274+ throw nav2_core::InvalidPath (" Requested path to smooth is invalid" );
275+ }
276+
273277 result->was_completed = smoothers_[current_smoother_]->smooth (
274278 result->path , goal->max_smoothing_duration );
275279 result->smoothing_duration = steady_clock_.now () - start_time;
@@ -283,6 +287,7 @@ void SmootherServer::smoothPlan()
283287 rclcpp::Duration (goal->max_smoothing_duration ).seconds (),
284288 rclcpp::Duration (result->smoothing_duration ).seconds ());
285289 }
290+
286291 plan_publisher_->publish (result->path );
287292
288293 // Check for collisions
@@ -299,8 +304,11 @@ void SmootherServer::smoothPlan()
299304 get_logger (),
300305 " Smoothed path leads to a collision at x: %lf, y: %lf, theta: %lf" ,
301306 pose2d.x , pose2d.y , pose2d.theta );
302- action_server_->terminate_current (result);
303- return ;
307+ throw nav2_core::SmoothedPathInCollision (
308+ " Smoothed Path collided at"
309+ " X: " + std::to_string (pose2d.x ) +
310+ " Y: " + std::to_string (pose2d.y ) +
311+ " Theta: " + std::to_string (pose2d.theta ));
304312 }
305313 fetch_data = false ;
306314 }
@@ -311,13 +319,50 @@ void SmootherServer::smoothPlan()
311319 rclcpp::Duration (result->smoothing_duration ).seconds ());
312320
313321 action_server_->succeeded_current (result);
314- } catch (nav2_core::PlannerException & e) {
315- RCLCPP_ERROR (this ->get_logger (), e.what ());
316- action_server_->terminate_current ();
322+ } catch (nav2_core::InvalidSmoother & ex) {
323+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
324+ result->error_code = ActionGoal::INVALID_SMOOTHER;
325+ action_server_->terminate_current (result);
326+ return ;
327+ } catch (nav2_core::SmootherTimedOut & ex) {
328+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
329+ result->error_code = ActionGoal::TIMEOUT;
330+ action_server_->terminate_current (result);
331+ return ;
332+ } catch (nav2_core::SmoothedPathInCollision & ex) {
333+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
334+ result->error_code = ActionGoal::SMOOTHED_PATH_IN_COLLISION;
335+ action_server_->terminate_current (result);
336+ return ;
337+ } catch (nav2_core::FailedToSmoothPath & ex) {
338+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
339+ result->error_code = ActionGoal::FAILED_TO_SMOOTH_PATH;
340+ action_server_->terminate_current (result);
341+ return ;
342+ } catch (nav2_core::InvalidPath & ex) {
343+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
344+ result->error_code = ActionGoal::INVALID_PATH;
345+ action_server_->terminate_current (result);
346+ return ;
347+ } catch (nav2_core::SmootherException & ex) {
348+ RCLCPP_ERROR (this ->get_logger (), " %s" , ex.what ());
349+ result->error_code = ActionGoal::UNKNOWN;
350+ action_server_->terminate_current (result);
317351 return ;
318352 }
319353}
320354
355+ bool SmootherServer::validate (const nav_msgs::msg::Path & path)
356+ {
357+ if (path.poses .empty ()) {
358+ RCLCPP_WARN (get_logger (), " Requested path to smooth is empty" );
359+ return false ;
360+ }
361+
362+ RCLCPP_DEBUG (get_logger (), " Requested path to smooth is valid" );
363+ return true ;
364+ }
365+
321366} // namespace nav2_smoother
322367
323368#include " rclcpp_components/register_node_macro.hpp"
0 commit comments