diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index dff1207b88..0eff064a5d 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -71,11 +71,13 @@ class GlobalPlanner * @brief Method create the plan from a starting and ending goal. * @param start The starting pose of the robot * @param goal The goal pose of the robot + * @param cancel_checker Function to check if the action has been canceled * @return The sequence of poses to get from start to goal, if any */ virtual nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) = 0; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) = 0; }; } // namespace nav2_core diff --git a/nav2_core/include/nav2_core/planner_exceptions.hpp b/nav2_core/include/nav2_core/planner_exceptions.hpp index 2680b3c669..c16c1c1096 100644 --- a/nav2_core/include/nav2_core/planner_exceptions.hpp +++ b/nav2_core/include/nav2_core/planner_exceptions.hpp @@ -113,6 +113,13 @@ class NoViapointsGiven : public PlannerException : PlannerException(description) {} }; +class PlannerCancelled : public PlannerException +{ +public: + explicit PlannerCancelled(const std::string & description) + : PlannerException(description) {} +}; + } // namespace nav2_core #endif // NAV2_CORE__PLANNER_EXCEPTIONS_HPP_ diff --git a/nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp b/nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp index a4ce84404a..966a845852 100644 --- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp +++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp @@ -43,6 +43,7 @@ #include #include #include +#include namespace nav2_navfn_planner { @@ -131,14 +132,16 @@ class NavFn /** * @brief Calculates a plan using the A* heuristic, returns true if one is found + * @param cancelChecker Function to check if the task has been canceled * @return True if a plan is found, false otherwise */ - bool calcNavFnAstar(); + bool calcNavFnAstar(std::function cancelChecker); /** - * @brief Caclulates the full navigation function using Dijkstra + * @brief Calculates the full navigation function using Dijkstra + * @param cancelChecker Function to check if the task has been canceled */ - bool calcNavFnDijkstra(bool atStart = false); + bool calcNavFnDijkstra(std::function cancelChecker, bool atStart = false); /** * @brief Accessor for the x-coordinates of a path @@ -179,6 +182,9 @@ class NavFn float curT; /**< current threshold */ float priInc; /**< priority threshold increment */ + /**< number of cycles between checks for cancellation */ + static constexpr int terminal_checking_interval = 5000; + /** goal and start positions */ /** * @brief Sets the goal position for the planner. @@ -229,18 +235,20 @@ class NavFn * @brief Run propagation for iterations, or until start is reached using * breadth-first Dijkstra method * @param cycles The maximum number of iterations to run for + * @param cancelChecker Function to check if the task has been canceled * @param atStart Whether or not to stop when the start point is reached * @return true if the start point is reached */ - bool propNavFnDijkstra(int cycles, bool atStart = false); + bool propNavFnDijkstra(int cycles, std::function cancelChecker, bool atStart = false); /** * @brief Run propagation for iterations, or until start is reached using * the best-first A* method with Euclidean distance heuristic * @param cycles The maximum number of iterations to run for + * @param cancelChecker Function to check if the task has been canceled * @return true if the start point is reached */ - bool propNavFnAstar(int cycles); /**< returns true if start point found */ + bool propNavFnAstar(int cycles, std::function cancelChecker); /** gradient and paths */ float * gradx, * grady; /**< gradient arrays, size of potential array */ diff --git a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp index 2330a5165b..c1cebb1bef 100644 --- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp +++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp @@ -81,11 +81,13 @@ class NavfnPlanner : public nav2_core::GlobalPlanner * @brief Creating a plan from start and goal poses * @param start Start pose * @param goal Goal pose + * @param cancel_checker Function to check if the task has been canceled * @return nav_msgs::Path of the generated path */ nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) override; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) override; protected: /** @@ -93,12 +95,14 @@ class NavfnPlanner : public nav2_core::GlobalPlanner * @param start Start pose * @param goal Goal pose * @param tolerance Relaxation constraint in x and y + * @param cancel_checker Function to check if the task has been canceled * @param plan Path to be computed * @return true if can find the path */ bool makePlan( const geometry_msgs::msg::Pose & start, const geometry_msgs::msg::Pose & goal, double tolerance, + std::function cancel_checker, nav_msgs::msg::Path & plan); /** diff --git a/nav2_navfn_planner/src/navfn.cpp b/nav2_navfn_planner/src/navfn.cpp index 8259950b03..2cce713b0f 100644 --- a/nav2_navfn_planner/src/navfn.cpp +++ b/nav2_navfn_planner/src/navfn.cpp @@ -44,6 +44,7 @@ #include "nav2_navfn_planner/navfn.hpp" #include +#include "nav2_core/planner_exceptions.hpp" #include "rclcpp/rclcpp.hpp" namespace nav2_navfn_planner @@ -293,12 +294,12 @@ NavFn::setCostmap(const COSTTYPE * cmap, bool isROS, bool allow_unknown) } bool -NavFn::calcNavFnDijkstra(bool atStart) +NavFn::calcNavFnDijkstra(std::function cancelChecker, bool atStart) { setupNavFn(true); // calculate the nav fn and path - return propNavFnDijkstra(std::max(nx * ny / 20, nx + ny), atStart); + return propNavFnDijkstra(std::max(nx * ny / 20, nx + ny), cancelChecker, atStart); } @@ -307,12 +308,12 @@ NavFn::calcNavFnDijkstra(bool atStart) // bool -NavFn::calcNavFnAstar() +NavFn::calcNavFnAstar(std::function cancelChecker) { setupNavFn(true); // calculate the nav fn and path - return propNavFnAstar(std::max(nx * ny / 20, nx + ny)); + return propNavFnAstar(std::max(nx * ny / 20, nx + ny), cancelChecker); } // @@ -571,7 +572,7 @@ NavFn::updateCellAstar(int n) // bool -NavFn::propNavFnDijkstra(int cycles, bool atStart) +NavFn::propNavFnDijkstra(int cycles, std::function cancelChecker, bool atStart) { int nwv = 0; // max priority block size int nc = 0; // number of cells put into priority blocks @@ -581,6 +582,10 @@ NavFn::propNavFnDijkstra(int cycles, bool atStart) int startCell = start[1] * nx + start[0]; for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted + if (cycle % terminal_checking_interval == 0 && cancelChecker()) { + throw nav2_core::PlannerCancelled("Planner was cancelled"); + } + if (curPe == 0 && nextPe == 0) { // priority blocks empty break; } @@ -652,7 +657,7 @@ NavFn::propNavFnDijkstra(int cycles, bool atStart) // bool -NavFn::propNavFnAstar(int cycles) +NavFn::propNavFnAstar(int cycles, std::function cancelChecker) { int nwv = 0; // max priority block size int nc = 0; // number of cells put into priority blocks @@ -667,6 +672,10 @@ NavFn::propNavFnAstar(int cycles) // do main cycle for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted + if (cycle % terminal_checking_interval == 0 && cancelChecker()) { + throw nav2_core::PlannerCancelled("Planner was cancelled"); + } + if (curPe == 0 && nextPe == 0) { // priority blocks empty break; } diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index 2ee8d69f53..9985280159 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -129,7 +129,8 @@ NavfnPlanner::cleanup() nav_msgs::msg::Path NavfnPlanner::createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) { #ifdef BENCHMARK_TESTING steady_clock::time_point a = steady_clock::now(); @@ -183,7 +184,7 @@ nav_msgs::msg::Path NavfnPlanner::createPlan( return path; } - if (!makePlan(start.pose, goal.pose, tolerance_, path)) { + if (!makePlan(start.pose, goal.pose, tolerance_, cancel_checker, path)) { throw nav2_core::NoValidPathCouldBeFound( "Failed to create plan with tolerance of: " + std::to_string(tolerance_) ); } @@ -214,6 +215,7 @@ bool NavfnPlanner::makePlan( const geometry_msgs::msg::Pose & start, const geometry_msgs::msg::Pose & goal, double tolerance, + std::function cancel_checker, nav_msgs::msg::Path & plan) { // clear the plan, just in case @@ -261,9 +263,9 @@ NavfnPlanner::makePlan( planner_->setStart(map_goal); planner_->setGoal(map_start); if (use_astar_) { - planner_->calcNavFnAstar(); + planner_->calcNavFnAstar(cancel_checker); } else { - planner_->calcNavFnDijkstra(true); + planner_->calcNavFnDijkstra(cancel_checker, true); } double resolution = costmap_->getResolution(); diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp index 7d2c9d03f0..bdffda281a 100644 --- a/nav2_planner/include/nav2_planner/planner_server.hpp +++ b/nav2_planner/include/nav2_planner/planner_server.hpp @@ -68,12 +68,15 @@ class PlannerServer : public nav2_util::LifecycleNode * @brief Method to get plan from the desired plugin * @param start starting pose * @param goal goal request + * @param planner_id The planner to plan with + * @param cancel_checker A function to check if the action has been canceled * @return Path */ nav_msgs::msg::Path getPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, - const std::string & planner_id); + const std::string & planner_id, + std::function cancel_checker); protected: /** diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index de239b3587..7f8dc4a72d 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -394,6 +394,10 @@ void PlannerServer::computePlanThroughPoses() throw nav2_core::PlannerTFError("Unable to get start pose"); } + auto cancel_checker = [this]() { + return action_server_poses_->is_cancel_requested(); + }; + // Get consecutive paths through these points for (unsigned int i = 0; i != goal->goals.size(); i++) { // Get starting point @@ -413,7 +417,9 @@ void PlannerServer::computePlanThroughPoses() } // Get plan from start -> goal - nav_msgs::msg::Path curr_path = getPlan(curr_start, curr_goal, goal->planner_id); + nav_msgs::msg::Path curr_path = getPlan( + curr_start, curr_goal, goal->planner_id, + cancel_checker); if (!validatePath(curr_goal, curr_path, goal->planner_id)) { throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path"); @@ -476,6 +482,9 @@ void PlannerServer::computePlanThroughPoses() exceptionWarning(curr_start, curr_goal, goal->planner_id, ex); result->error_code = ActionThroughPosesResult::NO_VIAPOINTS_GIVEN; action_server_poses_->terminate_current(result); + } catch (nav2_core::PlannerCancelled &) { + RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action."); + action_server_poses_->terminate_all(); } catch (std::exception & ex) { exceptionWarning(curr_start, curr_goal, goal->planner_id, ex); result->error_code = ActionThroughPosesResult::UNKNOWN; @@ -516,7 +525,11 @@ PlannerServer::computePlan() throw nav2_core::PlannerTFError("Unable to transform poses to global frame"); } - result->path = getPlan(start, goal_pose, goal->planner_id); + auto cancel_checker = [this]() { + return action_server_pose_->is_cancel_requested(); + }; + + result->path = getPlan(start, goal_pose, goal->planner_id, cancel_checker); if (!validatePath(goal_pose, result->path, goal->planner_id)) { throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path"); @@ -567,6 +580,9 @@ PlannerServer::computePlan() exceptionWarning(start, goal->goal, goal->planner_id, ex); result->error_code = ActionToPoseResult::TF_ERROR; action_server_pose_->terminate_current(result); + } catch (nav2_core::PlannerCancelled &) { + RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action."); + action_server_pose_->terminate_all(); } catch (std::exception & ex) { exceptionWarning(start, goal->goal, goal->planner_id, ex); result->error_code = ActionToPoseResult::UNKNOWN; @@ -578,7 +594,8 @@ nav_msgs::msg::Path PlannerServer::getPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, - const std::string & planner_id) + const std::string & planner_id, + std::function cancel_checker) { RCLCPP_DEBUG( get_logger(), "Attempting to a find path from (%.2f, %.2f) to " @@ -586,14 +603,14 @@ PlannerServer::getPlan( goal.pose.position.x, goal.pose.position.y); if (planners_.find(planner_id) != planners_.end()) { - return planners_[planner_id]->createPlan(start, goal); + return planners_[planner_id]->createPlan(start, goal, cancel_checker); } else { if (planners_.size() == 1 && planner_id.empty()) { RCLCPP_WARN_ONCE( get_logger(), "No planners specified in action call. " "Server will use only plugin %s in server." " This warning will appear once.", planner_ids_concat_.c_str()); - return planners_[planners_.begin()->first]->createPlan(start, goal); + return planners_[planners_.begin()->first]->createPlan(start, goal, cancel_checker); } else { RCLCPP_ERROR( get_logger(), "planner %s is not a valid planner. " diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 3a992088b6..6e92209068 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -109,6 +109,7 @@ planner_server: allow_unknown: false # allow traveling in unknown space max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance + terminal_checking_interval: 5000 # number of iterations between checking if the goal has been cancelled or planner timed out max_planning_time: 3.5 # max time in s for planner to plan, smooth, and upsample. Will scale maximum smoothing and upsampling times based on remaining time after planning. motion_model_for_search: "DUBIN" # For Hybrid Dubin, Redds-Shepp cost_travel_multiplier: 2.0 # For 2D: Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*. diff --git a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp index e4ecf38f03..668aff5e4d 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -88,6 +88,8 @@ class AStarAlgorithm * @param max_on_approach_iterations Maximum number of iterations before returning a valid * path once within thresholds to refine path * comes at more compute time but smoother paths. + * @param terminal_checking_interval Number of iterations to check if the task has been canceled or + * or planning time exceeded * @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns * false after this timeout */ @@ -95,6 +97,7 @@ class AStarAlgorithm const bool & allow_unknown, int & max_iterations, const int & max_on_approach_iterations, + const int & terminal_checking_interval, const double & max_planning_time, const float & lookup_table_size, const unsigned int & dim_3_size); @@ -104,11 +107,13 @@ class AStarAlgorithm * @param path Reference to a vector of indicies of generated path * @param num_iterations Reference to number of iterations to create plan * @param tolerance Reference to tolerance in costmap nodes + * @param cancel_checker Function to check if the task has been canceled * @param expansions_log Optional expansions logged for debug * @return if plan was successful */ bool createPath( CoordinateVector & path, int & num_iterations, const float & tolerance, + std::function cancel_checker, std::vector> * expansions_log = nullptr); /** @@ -250,11 +255,11 @@ class AStarAlgorithm */ void clearStart(); - int _timing_interval = 5000; bool _traverse_unknown; int _max_iterations; int _max_on_approach_iterations; + int _terminal_checking_interval; double _max_planning_time; float _tolerance; unsigned int _x_size; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp index c499d0796f..059871d867 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp @@ -82,11 +82,13 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner * @brief Creating a plan from start and goal poses * @param start Start pose * @param goal Goal pose + * @param cancel_checker Function to check if the action has been canceled * @return nav2_msgs::Path of the generated path */ nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) override; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) override; protected: /** @@ -112,6 +114,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner bool _allow_unknown; int _max_iterations; int _max_on_approach_iterations; + int _terminal_checking_interval; bool _use_final_approach_orientation; SearchInfo _search_info; std::string _motion_model_for_search; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp index fae139aa2f..157bbcea83 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp @@ -81,11 +81,13 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner * @brief Creating a plan from start and goal poses * @param start Start pose * @param goal Goal pose + * @param cancel_checker Function to check if the action has been canceled * @return nav2_msgs::Path of the generated path */ nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) override; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) override; protected: /** @@ -113,6 +115,7 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner bool _allow_unknown; int _max_iterations; int _max_on_approach_iterations; + int _terminal_checking_interval; SearchInfo _search_info; double _max_planning_time; double _lookup_table_size; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index ce8bafd2fd..57e225f287 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -80,11 +80,13 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner * @brief Creating a plan from start and goal poses * @param start Start pose * @param goal Goal pose + * @param cancel_checker Function to check if the action has been canceled * @return nav2_msgs::Path of the generated path */ nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) override; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) override; protected: /** @@ -108,6 +110,7 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner bool _allow_unknown; int _max_iterations; int _max_on_approach_iterations; + int _terminal_checking_interval; float _tolerance; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; double _max_planning_time; diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index ebade0f4aa..1f0d720763 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -37,6 +37,7 @@ AStarAlgorithm::AStarAlgorithm( const SearchInfo & search_info) : _traverse_unknown(true), _max_iterations(0), + _terminal_checking_interval(5000), _max_planning_time(0), _x_size(0), _y_size(0), @@ -59,6 +60,7 @@ void AStarAlgorithm::initialize( const bool & allow_unknown, int & max_iterations, const int & max_on_approach_iterations, + const int & terminal_checking_interval, const double & max_planning_time, const float & lookup_table_size, const unsigned int & dim_3_size) @@ -66,6 +68,7 @@ void AStarAlgorithm::initialize( _traverse_unknown = allow_unknown; _max_iterations = max_iterations; _max_on_approach_iterations = max_on_approach_iterations; + _terminal_checking_interval = terminal_checking_interval; _max_planning_time = max_planning_time; NodeT::precomputeDistanceHeuristic(lookup_table_size, _motion_model, dim_3_size, _search_info); _dim3_size = dim_3_size; @@ -78,6 +81,7 @@ void AStarAlgorithm::initialize( const bool & allow_unknown, int & max_iterations, const int & max_on_approach_iterations, + const int & terminal_checking_interval, const double & max_planning_time, const float & /*lookup_table_size*/, const unsigned int & dim_3_size) @@ -85,6 +89,7 @@ void AStarAlgorithm::initialize( _traverse_unknown = allow_unknown; _max_iterations = max_iterations; _max_on_approach_iterations = max_on_approach_iterations; + _terminal_checking_interval = terminal_checking_interval; _max_planning_time = max_planning_time; if (dim_3_size != 1) { @@ -245,6 +250,7 @@ template bool AStarAlgorithm::createPath( CoordinateVector & path, int & iterations, const float & tolerance, + std::function cancel_checker, std::vector> * expansions_log) { steady_clock::time_point start_time = steady_clock::now(); @@ -285,8 +291,11 @@ bool AStarAlgorithm::createPath( }; while (iterations < getMaxIterations() && !_queue.empty()) { - // Check for planning timeout only on every Nth iteration - if (iterations % _timing_interval == 0) { + // Check for planning timeout and cancel only on every Nth iteration + if (iterations % _terminal_checking_interval == 0) { + if (cancel_checker()) { + throw nav2_core::PlannerCancelled("Planner was cancelled"); + } std::chrono::duration planning_duration = std::chrono::duration_cast>(steady_clock::now() - start_time); if (static_cast(planning_duration.count()) >= _max_planning_time) { diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index 70f8852f28..38fd12b9e1 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -83,6 +83,9 @@ void SmacPlanner2D::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); + nav2_util::declare_parameter_if_not_declared( + node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); + node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); nav2_util::declare_parameter_if_not_declared( node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false)); node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation); @@ -120,6 +123,7 @@ void SmacPlanner2D::configure( _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, 0.0 /*unused for 2D*/, 1.0 /*unused for 2D*/); @@ -192,7 +196,8 @@ void SmacPlanner2D::cleanup() nav_msgs::msg::Path SmacPlanner2D::createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) { std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); @@ -257,7 +262,7 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( // Note: All exceptions thrown are handled by the planner server and returned to the action if (!_a_star->createPath( path, num_iterations, - _tolerance / static_cast(costmap->getResolution()))) + _tolerance / static_cast(costmap->getResolution()), cancel_checker)) { // Note: If the start is blocked only one iteration will occur before failure if (num_iterations == 1) { @@ -377,6 +382,9 @@ SmacPlanner2D::dynamicParametersCallback(std::vector paramete "disabling tolerance and on approach iterations."); _max_on_approach_iterations = std::numeric_limits::max(); } + } else if (name == _name + ".terminal_checking_interval") { + reinit_a_star = true; + _terminal_checking_interval = parameter.as_int(); } } } @@ -390,6 +398,7 @@ SmacPlanner2D::dynamicParametersCallback(std::vector paramete _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, 0.0 /*unused for 2D*/, 1.0 /*unused for 2D*/); diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 727e4c08b2..b0bdf042dc 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -94,6 +94,9 @@ void SmacPlannerHybrid::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); + nav2_util::declare_parameter_if_not_declared( + node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); + node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); nav2_util::declare_parameter_if_not_declared( node, name + ".smooth_path", rclcpp::ParameterValue(true)); node->get_parameter(name + ".smooth_path", smooth_path); @@ -228,6 +231,7 @@ void SmacPlannerHybrid::configure( _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, _lookup_table_dim, _angle_quantizations); @@ -318,7 +322,8 @@ void SmacPlannerHybrid::cleanup() nav_msgs::msg::Path SmacPlannerHybrid::createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) { std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); @@ -394,7 +399,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( // Note: All exceptions thrown are handled by the planner server and returned to the action if (!_a_star->createPath( path, num_iterations, - _tolerance / static_cast(costmap->getResolution()), expansions.get())) + _tolerance / static_cast(costmap->getResolution()), cancel_checker, expansions.get())) { if (_debug_visualizations) { geometry_msgs::msg::PoseArray msg; @@ -598,6 +603,9 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector para "disabling tolerance and on approach iterations."); _max_on_approach_iterations = std::numeric_limits::max(); } + } else if (name == _name + ".terminal_checking_interval") { + reinit_a_star = true; + _terminal_checking_interval = parameter.as_int(); } else if (name == _name + ".angle_quantization_bins") { reinit_collision_checker = true; reinit_a_star = true; @@ -653,6 +661,7 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector para _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, _lookup_table_dim, _angle_quantizations); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 1666c7a9ce..cd98cf6440 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -77,6 +77,9 @@ void SmacPlannerLattice::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); + nav2_util::declare_parameter_if_not_declared( + node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); + node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); nav2_util::declare_parameter_if_not_declared( node, name + ".smooth_path", rclcpp::ParameterValue(true)); node->get_parameter(name + ".smooth_path", smooth_path); @@ -193,6 +196,7 @@ void SmacPlannerLattice::configure( _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, lookup_table_dim, _metadata.number_of_headings); @@ -261,7 +265,8 @@ void SmacPlannerLattice::cleanup() nav_msgs::msg::Path SmacPlannerLattice::createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) { std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); @@ -316,7 +321,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( // Note: All exceptions thrown are handled by the planner server and returned to the action if (!_a_star->createPath( path, num_iterations, - _tolerance / static_cast(_costmap->getResolution()), expansions.get())) + _tolerance / static_cast(_costmap->getResolution()), cancel_checker, expansions.get())) { if (_debug_visualizations) { geometry_msgs::msg::PoseArray msg; @@ -504,15 +509,18 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par "disabling maximum iterations."); _max_iterations = std::numeric_limits::max(); } - } - } else if (name == _name + ".max_on_approach_iterations") { - reinit_a_star = true; - _max_on_approach_iterations = parameter.as_int(); - if (_max_on_approach_iterations <= 0) { - RCLCPP_INFO( - _logger, "On approach iteration selected as <= 0, " - "disabling tolerance and on approach iterations."); - _max_on_approach_iterations = std::numeric_limits::max(); + } else if (name == _name + ".max_on_approach_iterations") { + reinit_a_star = true; + _max_on_approach_iterations = parameter.as_int(); + if (_max_on_approach_iterations <= 0) { + RCLCPP_INFO( + _logger, "On approach iteration selected as <= 0, " + "disabling tolerance and on approach iterations."); + _max_on_approach_iterations = std::numeric_limits::max(); + } + } else if (name == _name + ".terminal_checking_interval") { + reinit_a_star = true; + _terminal_checking_interval = parameter.as_int(); } } else if (type == ParameterType::PARAMETER_STRING) { if (name == _name + ".lattice_filepath") { @@ -565,6 +573,7 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par _allow_unknown, _max_iterations, _max_on_approach_iterations, + _terminal_checking_interval, _max_planning_time, lookup_table_dim, _metadata.number_of_headings); diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index 13c2c80298..bdcf37c721 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -47,10 +47,13 @@ TEST(AStarTest, test_a_star_2d) float tolerance = 0.0; float some_tolerance = 20.0; int it_on_approach = 10; + int terminal_checking_interval = 5000; double max_planning_time = 120.0; int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach, max_planning_time, 0.0, 1); + a_star.initialize( + false, max_iterations, it_on_approach, terminal_checking_interval, + max_planning_time, 0.0, 1); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); @@ -67,6 +70,10 @@ TEST(AStarTest, test_a_star_2d) auto costmap = costmap_ros->getCostmap(); *costmap = *costmapA; + auto dummy_cancel_checker = []() { + return false; + }; + // functional case testing std::unique_ptr checker = std::make_unique(costmap_ros, 1, lnode); @@ -75,7 +82,7 @@ TEST(AStarTest, test_a_star_2d) a_star.setStart(20u, 20u, 0); a_star.setGoal(80u, 80u, 0); nav2_smac_planner::Node2D::CoordinateVector path; - EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker)); EXPECT_EQ(num_it, 2414); // check path is the right size and collision free @@ -92,21 +99,32 @@ TEST(AStarTest, test_a_star_2d) // failure cases with invalid inputs nav2_smac_planner::AStarAlgorithm a_star_2( nav2_smac_planner::MotionModel::TWOD, info); - a_star_2.initialize(false, max_iterations, it_on_approach, max_planning_time, 0, 1); + a_star_2.initialize( + false, max_iterations, it_on_approach, terminal_checking_interval, + max_planning_time, 0, 1); num_it = 0; - EXPECT_THROW(a_star_2.createPath(path, num_it, tolerance), std::runtime_error); + EXPECT_THROW( + a_star_2.createPath( + path, num_it, tolerance, + dummy_cancel_checker), std::runtime_error); a_star_2.setCollisionChecker(checker.get()); num_it = 0; - EXPECT_THROW(a_star_2.createPath(path, num_it, tolerance), std::runtime_error); + EXPECT_THROW( + a_star_2.createPath( + path, num_it, tolerance, + dummy_cancel_checker), std::runtime_error); a_star_2.setStart(0, 0, 0); // valid a_star_2.setGoal(50, 50, 0); // invalid num_it = 0; - EXPECT_THROW(a_star_2.createPath(path, num_it, tolerance), std::runtime_error); + EXPECT_THROW( + a_star_2.createPath( + path, num_it, tolerance, + dummy_cancel_checker), std::runtime_error); num_it = 0; // invalid goal but liberal tolerance a_star_2.setStart(20, 20, 0); // valid a_star_2.setGoal(50, 50, 0); // invalid - EXPECT_TRUE(a_star_2.createPath(path, num_it, some_tolerance)); + EXPECT_TRUE(a_star_2.createPath(path, num_it, some_tolerance, dummy_cancel_checker)); EXPECT_EQ(path.size(), 21u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); @@ -141,10 +159,13 @@ TEST(AStarTest, test_a_star_se2) int max_iterations = 10000; float tolerance = 10.0; int it_on_approach = 10; + int terminal_checking_interval = 5000; double max_planning_time = 120.0; int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach, max_planning_time, 401, size_theta); + a_star.initialize( + false, max_iterations, it_on_approach, terminal_checking_interval, + max_planning_time, 401, size_theta); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); @@ -173,7 +194,11 @@ TEST(AStarTest, test_a_star_se2) std::unique_ptr>> expansions = nullptr; expansions = std::make_unique>>(); - EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, expansions.get())); + auto dummy_cancel_checker = []() { + return false; + }; + + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker, expansions.get())); // check path is the right size and collision free EXPECT_EQ(num_it, 3146); @@ -214,11 +239,14 @@ TEST(AStarTest, test_a_star_lattice) int max_iterations = 10000; float tolerance = 10.0; int it_on_approach = 10; + int terminal_checking_interval = 5000; double max_planning_time = 120.0; int num_it = 0; a_star.initialize( - false, max_iterations, std::numeric_limits::max(), max_planning_time, 401, size_theta); + false, max_iterations, + std::numeric_limits::max(), terminal_checking_interval, max_planning_time, 401, + size_theta); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.05, 0.0, 0.0, 0); @@ -239,12 +267,16 @@ TEST(AStarTest, test_a_star_lattice) std::make_unique(costmap_ros, size_theta, lnode); checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + auto dummy_cancel_checker = []() { + return false; + }; + // functional case testing a_star.setCollisionChecker(checker.get()); a_star.setStart(5u, 5u, 0u); a_star.setGoal(40u, 40u, 1u); nav2_smac_planner::NodeLattice::CoordinateVector path; - EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker)); // check path is the right size and collision free EXPECT_EQ(num_it, 22); @@ -278,10 +310,13 @@ TEST(AStarTest, test_se2_single_pose_path) int max_iterations = 100; float tolerance = 10.0; int it_on_approach = 10; + int terminal_checking_interval = 5000; double max_planning_time = 120.0; int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach, max_planning_time, 401, size_theta); + a_star.initialize( + false, max_iterations, it_on_approach, terminal_checking_interval, + max_planning_time, 401, size_theta); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); @@ -296,13 +331,16 @@ TEST(AStarTest, test_se2_single_pose_path) std::make_unique(costmap_ros, size_theta, lnode); checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + auto dummy_cancel_checker = []() { + return false; + }; // functional case testing a_star.setCollisionChecker(checker.get()); a_star.setStart(10u, 10u, 0u); // Goal is one costmap cell away a_star.setGoal(12u, 10u, 0u); nav2_smac_planner::NodeHybrid::CoordinateVector path; - EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker)); // Check that the path is length one // With the current implementation, this produces a longer path diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index 1ebe215b30..e2dff5a56f 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -57,6 +57,10 @@ TEST(SmacTest, test_smac_2d) { node2D->declare_parameter("test.downsampling_factor", 2); node2D->set_parameter(rclcpp::Parameter("test.downsampling_factor", 2)); + auto dummy_cancel_checker = []() { + return false; + }; + geometry_msgs::msg::PoseStamped start, goal; start.pose.position.x = 0.0; start.pose.position.y = 0.0; @@ -69,7 +73,7 @@ TEST(SmacTest, test_smac_2d) { planner_2d->configure(node2D, "test", nullptr, costmap_ros); planner_2d->activate(); try { - planner_2d->createPlan(start, goal); + planner_2d->createPlan(start, goal, dummy_cancel_checker); } catch (...) { } @@ -108,6 +112,7 @@ TEST(SmacTest, test_smac_2d_reconfigure) { rclcpp::Parameter("test.downsampling_factor", 2), rclcpp::Parameter("test.max_iterations", -1), rclcpp::Parameter("test.max_on_approach_iterations", -1), + rclcpp::Parameter("test.terminal_checking_interval", 100), rclcpp::Parameter("test.use_final_approach_orientation", false)}); rclcpp::spin_until_future_complete( @@ -127,6 +132,9 @@ TEST(SmacTest, test_smac_2d_reconfigure) { EXPECT_EQ( node2D->get_parameter("test.max_on_approach_iterations").as_int(), -1); + EXPECT_EQ( + node2D->get_parameter("test.terminal_checking_interval").as_int(), + 100); results = rec_param->set_parameters_atomically( {rclcpp::Parameter("test.downsample_costmap", true)}); diff --git a/nav2_smac_planner/test/test_smac_hybrid.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp index aae4666edc..a2af405d51 100644 --- a/nav2_smac_planner/test/test_smac_hybrid.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -56,6 +56,10 @@ TEST(SmacTest, test_smac_se2) nodeSE2->declare_parameter("test.downsampling_factor", 2); nodeSE2->set_parameter(rclcpp::Parameter("test.downsampling_factor", 2)); + auto dummy_cancel_checker = []() { + return false; + }; + geometry_msgs::msg::PoseStamped start, goal; start.pose.position.x = 0.0; start.pose.position.y = 0.0; @@ -68,7 +72,7 @@ TEST(SmacTest, test_smac_se2) planner->activate(); try { - planner->createPlan(start, goal); + planner->createPlan(start, goal, dummy_cancel_checker); } catch (...) { } @@ -119,6 +123,7 @@ TEST(SmacTest, test_smac_se2_reconfigure) rclcpp::Parameter("test.smooth_path", false), rclcpp::Parameter("test.analytic_expansion_max_length", 42.0), rclcpp::Parameter("test.max_on_approach_iterations", 42), + rclcpp::Parameter("test.terminal_checking_interval", 42), rclcpp::Parameter("test.motion_model_for_search", std::string("REEDS_SHEPP"))}); rclcpp::spin_until_future_complete( @@ -144,6 +149,7 @@ TEST(SmacTest, test_smac_se2_reconfigure) EXPECT_EQ(nodeSE2->get_parameter("test.lookup_table_size").as_double(), 30.0); EXPECT_EQ(nodeSE2->get_parameter("test.analytic_expansion_max_length").as_double(), 42.0); EXPECT_EQ(nodeSE2->get_parameter("test.max_on_approach_iterations").as_int(), 42); + EXPECT_EQ(nodeSE2->get_parameter("test.terminal_checking_interval").as_int(), 42); EXPECT_EQ( nodeSE2->get_parameter("test.motion_model_for_search").as_string(), std::string("REEDS_SHEPP")); diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index b791f9961c..dcc925e9e7 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -60,6 +60,10 @@ TEST(SmacTest, test_smac_lattice) std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); + auto dummy_cancel_checker = []() { + return false; + }; + geometry_msgs::msg::PoseStamped start, goal; start.pose.position.x = 0.0; start.pose.position.y = 0.0; @@ -76,7 +80,7 @@ TEST(SmacTest, test_smac_lattice) planner->activate(); try { - planner->createPlan(start, goal); + planner->createPlan(start, goal, dummy_cancel_checker); } catch (...) { } @@ -128,6 +132,7 @@ TEST(SmacTest, test_smac_lattice_reconfigure) rclcpp::Parameter("test.tolerance", 42.0), rclcpp::Parameter("test.rotation_penalty", 42.0), rclcpp::Parameter("test.max_on_approach_iterations", 42), + rclcpp::Parameter("test.terminal_checking_interval", 42), rclcpp::Parameter("test.allow_reverse_expansion", true)}); try { diff --git a/nav2_smac_planner/test/test_smoother.cpp b/nav2_smac_planner/test/test_smoother.cpp index 3844923498..616c674595 100644 --- a/nav2_smac_planner/test/test_smoother.cpp +++ b/nav2_smac_planner/test/test_smoother.cpp @@ -89,11 +89,14 @@ TEST(SmootherTest, test_full_smoother) int max_iterations = 10000; float tolerance = 10.0; int it_on_approach = 10; + int terminal_checking_interval = 5000; double max_planning_time = 120.0; int num_it = 0; a_star.initialize( - false, max_iterations, std::numeric_limits::max(), max_planning_time, 401, size_theta); + false, max_iterations, + std::numeric_limits::max(), terminal_checking_interval, max_planning_time, 401, + size_theta); // Convert raw costmap into a costmap ros object auto costmap_ros = std::make_shared(); @@ -105,12 +108,16 @@ TEST(SmootherTest, test_full_smoother) std::make_unique(costmap_ros, size_theta, node); checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + auto dummy_cancel_checker = []() { + return false; + }; + // Create A* search to smooth a_star.setCollisionChecker(checker.get()); a_star.setStart(5u, 5u, 0u); a_star.setGoal(45u, 45u, 36u); nav2_smac_planner::NodeHybrid::CoordinateVector path; - EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker)); // Convert to world coordinates and get length to compare to smoothed length nav_msgs::msg::Path plan; diff --git a/nav2_system_tests/src/error_codes/error_code_param.yaml b/nav2_system_tests/src/error_codes/error_code_param.yaml index 388e6f2cdb..7886fe6686 100644 --- a/nav2_system_tests/src/error_codes/error_code_param.yaml +++ b/nav2_system_tests/src/error_codes/error_code_param.yaml @@ -154,7 +154,7 @@ planner_server: expected_planner_frequency: 20.0 planner_plugins: [ "unknown", "tf_error", "start_outside_map", "goal_outside_map", "start_occupied", "goal_occupied", "timeout","no_valid_path", - "no_viapoints_given" ] + "no_viapoints_given", "cancelled" ] unknown: plugin: "nav2_system_tests::UnknownErrorPlanner" tf_error: @@ -173,6 +173,8 @@ planner_server: plugin: "nav2_system_tests::NoValidPathErrorPlanner" no_viapoints_given: plugin: "nav2_system_tests::NoViapointsGivenErrorPlanner" + cancelled: + plugin: "nav2_system_tests::CancelledPlanner" smoother_server: ros__parameters: diff --git a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.cpp b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.cpp index 90b18c5b11..1c2eecf23a 100644 --- a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.cpp +++ b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.cpp @@ -24,3 +24,4 @@ PLUGINLIB_EXPORT_CLASS(nav2_system_tests::NoValidPathErrorPlanner, nav2_core::Gl PLUGINLIB_EXPORT_CLASS(nav2_system_tests::TimedOutErrorPlanner, nav2_core::GlobalPlanner) PLUGINLIB_EXPORT_CLASS(nav2_system_tests::TFErrorPlanner, nav2_core::GlobalPlanner) PLUGINLIB_EXPORT_CLASS(nav2_system_tests::NoViapointsGivenErrorPlanner, nav2_core::GlobalPlanner) +PLUGINLIB_EXPORT_CLASS(nav2_system_tests::CancelledPlanner, nav2_core::GlobalPlanner) diff --git a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp index 2b6ae7971d..77b23aecce 100644 --- a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp +++ b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp @@ -51,7 +51,8 @@ class UnknownErrorPlanner : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::PlannerException("Unknown Error"); } @@ -61,7 +62,8 @@ class StartOccupiedErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::StartOccupied("Start Occupied"); } @@ -71,7 +73,8 @@ class GoalOccupiedErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::GoalOccupied("Goal occupied"); } @@ -81,7 +84,8 @@ class StartOutsideMapErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::StartOutsideMapBounds("Start OutsideMapBounds"); } @@ -91,7 +95,8 @@ class GoalOutsideMapErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::GoalOutsideMapBounds("Goal outside map bounds"); } @@ -101,7 +106,8 @@ class NoValidPathErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { return nav_msgs::msg::Path(); } @@ -112,7 +118,8 @@ class TimedOutErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::PlannerTimedOut("Planner Timed Out"); } @@ -122,7 +129,8 @@ class TFErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::PlannerTFError("TF Error"); } @@ -132,12 +140,33 @@ class NoViapointsGivenErrorPlanner : public UnknownErrorPlanner { nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, - const geometry_msgs::msg::PoseStamped &) override + const geometry_msgs::msg::PoseStamped &, + std::function) override { throw nav2_core::NoViapointsGiven("No Via points given"); } }; +class CancelledPlanner : public UnknownErrorPlanner +{ + nav_msgs::msg::Path createPlan( + const geometry_msgs::msg::PoseStamped &, + const geometry_msgs::msg::PoseStamped &, + std::function cancel_checker) override + { + auto start_time = std::chrono::steady_clock::now(); + while (rclcpp::ok() && + std::chrono::steady_clock::now() - start_time < std::chrono::seconds(5)) + { + if (cancel_checker()) { + throw nav2_core::PlannerCancelled("Planner Cancelled"); + } + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + throw nav2_core::PlannerException("Cancel is not called in time."); + } +}; + } // namespace nav2_system_tests diff --git a/nav2_system_tests/src/error_codes/planner_plugins.xml b/nav2_system_tests/src/error_codes/planner_plugins.xml index 9d6f7f0545..ab10ae800b 100644 --- a/nav2_system_tests/src/error_codes/planner_plugins.xml +++ b/nav2_system_tests/src/error_codes/planner_plugins.xml @@ -39,4 +39,8 @@ base_class_type="nav2_core::GlobalPlanner"> This global planner produces a no via points exception. + + This global planner produces a cancelled exception. + diff --git a/nav2_system_tests/src/error_codes/test_error_codes.py b/nav2_system_tests/src/error_codes/test_error_codes.py index f023bbb27c..a5f2b84d97 100755 --- a/nav2_system_tests/src/error_codes/test_error_codes.py +++ b/nav2_system_tests/src/error_codes/test_error_codes.py @@ -14,6 +14,7 @@ # limitations under the License. import sys +import threading import time from geometry_msgs.msg import PoseStamped @@ -23,7 +24,7 @@ FollowPath, SmoothPath, ) -from nav2_simple_commander.robot_navigator import BasicNavigator +from nav2_simple_commander.robot_navigator import BasicNavigator, TaskResult from nav_msgs.msg import Path import rclpy @@ -111,6 +112,17 @@ def main(argv=sys.argv[1:]): result.error_code == error_code ), 'Compute path to pose error does not match' + def cancel_task(): + time.sleep(1) + navigator.goal_handle.cancel_goal_async() + + # Check compute path to pose cancel + threading.Thread(target=cancel_task).start() + result = navigator._getPathImpl(initial_pose, goal_pose, 'cancelled') + assert ( + navigator.getResult() == TaskResult.CANCELED + ), 'Compute path to pose cancel failed' + # Check compute path through error codes goal_pose1 = goal_pose goal_poses = [goal_pose, goal_pose1] @@ -133,6 +145,12 @@ def main(argv=sys.argv[1:]): assert ( result.error_code == error_code ), 'Compute path through pose error does not match' + # Check compute path to pose cancel + threading.Thread(target=cancel_task).start() + result = navigator._getPathThroughPosesImpl(initial_pose, goal_poses, 'cancelled') + assert ( + navigator.getResult() == TaskResult.CANCELED + ), 'Compute path through poses cancel failed' # Check compute path to pose error codes pose = PoseStamped() diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index 7a5f8d4b7f..421a00f4b7 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -87,7 +87,8 @@ class NavFnPlannerTester : public nav2_planner::PlannerServer return false; } try { - path = planners_["GridBased"]->createPlan(start, goal); + auto dummy_cancel_checker = []() {return false;}; + path = planners_["GridBased"]->createPlan(start, goal, dummy_cancel_checker); // The situation when createPlan() did not throw any exception // does not guarantee that plan was created correctly. // So it should be checked additionally that path is correct. diff --git a/nav2_system_tests/src/planning/test_planner_plugins.cpp b/nav2_system_tests/src/planning/test_planner_plugins.cpp index 906e8f44d3..01d264006a 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -57,9 +57,11 @@ void testSmallPathValidityAndOrientation(std::string plugin, double length) goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI); goal.header.frame_id = "map"; + auto dummy_cancel_checker = []() {return false;}; + // Test without use_final_approach_orientation // expecting end path pose orientation to be equal to goal orientation - auto path = obj->getPlan(start, goal, "GridBased"); + auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker); EXPECT_GT((int)path.poses.size(), 0); EXPECT_NEAR(tf2::getYaw(path.poses.back().pose.orientation), -M_PI, 0.01); // obj->onCleanup(state); @@ -93,7 +95,9 @@ void testSmallPathValidityAndNoOrientation(std::string plugin, double length) goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI); goal.header.frame_id = "map"; - auto path = obj->getPlan(start, goal, "GridBased"); + auto dummy_cancel_checker = []() {return false;}; + + auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker); EXPECT_GT((int)path.poses.size(), 0); int path_size = path.poses.size(); @@ -114,6 +118,36 @@ void testSmallPathValidityAndNoOrientation(std::string plugin, double length) obj.reset(); } +void testCancel(std::string plugin) +{ + auto obj = std::make_shared(); + rclcpp_lifecycle::State state; + obj->set_parameter(rclcpp::Parameter("GridBased.plugin", plugin)); + obj->declare_parameter("GridBased.terminal_checking_interval", rclcpp::ParameterValue(1)); + obj->onConfigure(state); + + geometry_msgs::msg::PoseStamped start; + geometry_msgs::msg::PoseStamped goal; + + start.pose.position.x = 0.0; + start.pose.position.y = 0.0; + start.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(M_PI_2); + start.header.frame_id = "map"; + + goal.pose.position.x = 0.5; + goal.pose.position.y = 0.6; + goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI); + goal.header.frame_id = "map"; + + auto always_cancelled = []() {return true;}; + + EXPECT_THROW( + obj->getPlan(start, goal, "GridBased", always_cancelled), + nav2_core::PlannerCancelled); + // obj->onCleanup(state); + obj.reset(); +} + TEST(testPluginMap, Failures) { auto obj = std::make_shared(); @@ -127,11 +161,14 @@ TEST(testPluginMap, Failures) geometry_msgs::msg::PoseStamped goal; std::string plugin_fake = "fake"; std::string plugin_none = ""; - auto path = obj->getPlan(start, goal, plugin_none); + + auto dummy_cancel_checker = []() {return false;}; + + auto path = obj->getPlan(start, goal, plugin_none, dummy_cancel_checker); EXPECT_EQ(path.header.frame_id, std::string("map")); try { - path = obj->getPlan(start, goal, plugin_fake); + path = obj->getPlan(start, goal, plugin_fake, dummy_cancel_checker); FAIL() << "Failed to throw invalid planner id exception"; } catch (const nav2_core::InvalidPlanner & ex) { EXPECT_EQ(ex.what(), std::string("Planner id fake is invalid")); @@ -140,6 +177,7 @@ TEST(testPluginMap, Failures) obj->onCleanup(state); } + TEST(testPluginMap, Smac2dEqualStartGoal) { testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.0); @@ -290,6 +328,32 @@ TEST(testPluginMap, ThetaStarAboveCostmapResolutionN) testSmallPathValidityAndNoOrientation("nav2_theta_star_planner/ThetaStarPlanner", 1.5); } +TEST(testPluginMap, NavFnCancel) +{ + testCancel("nav2_navfn_planner/NavfnPlanner"); +} + +TEST(testPluginMap, ThetaStarCancel) +{ + testCancel("nav2_theta_star_planner/ThetaStarPlanner"); +} + +TEST(testPluginMap, Smac2dCancel) +{ + testCancel("nav2_smac_planner/SmacPlanner2D"); +} + +TEST(testPluginMap, SmacLatticeCancel) +{ + testCancel("nav2_smac_planner/SmacPlannerLattice"); +} + +TEST(testPluginMap, SmacHybridAStarCancel) +{ + testCancel("nav2_smac_planner/SmacPlannerHybrid"); +} + + int main(int argc, char ** argv) { ::testing::InitGoogleTest(&argc, argv); diff --git a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star.hpp b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star.hpp index a58a4f87ed..1c819a882e 100644 --- a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star.hpp +++ b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star.hpp @@ -76,6 +76,8 @@ class ThetaStar bool allow_unknown_; /// the x-directional and y-directional lengths of the map respectively int size_x_, size_y_; + /// the interval at which the planner checks if it has been cancelled + int terminal_checking_interval_; ThetaStar(); @@ -87,7 +89,7 @@ class ThetaStar * @param raw_path is used to return the path obtained by executing the algorithm * @return true if a path is found, false if no path is found in between the start and goal pose */ - bool generatePath(std::vector & raw_path); + bool generatePath(std::vector & raw_path, std::function cancel_checker); /** * @brief this function checks whether the cost of a point(cx, cy) on the costmap is less than the LETHAL_COST diff --git a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp index bcbff2ae7c..09f8714219 100644 --- a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp +++ b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp @@ -54,9 +54,17 @@ class ThetaStarPlanner : public nav2_core::GlobalPlanner void deactivate() override; + /** + * @brief Creating a plan from start and goal poses + * @param start Start pose + * @param goal Goal pose + * @param cancel_checker Function to check if the action has been canceled + * @return nav2_msgs::Path of the generated path + */ nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) override; + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) override; protected: std::shared_ptr tf_; @@ -76,9 +84,10 @@ class ThetaStarPlanner : public nav2_core::GlobalPlanner /** * @brief the function responsible for calling the algorithm and retrieving a path from it + * @param cancel_checker is a function to check if the action has been canceled * @return global_path is the planned path to be taken */ - void getPlan(nav_msgs::msg::Path & global_path); + void getPlan(nav_msgs::msg::Path & global_path, std::function cancel_checker); /** * @brief interpolates points between the consecutive waypoints of the path diff --git a/nav2_theta_star_planner/src/theta_star.cpp b/nav2_theta_star_planner/src/theta_star.cpp index f83b745b22..ba3629bcbf 100644 --- a/nav2_theta_star_planner/src/theta_star.cpp +++ b/nav2_theta_star_planner/src/theta_star.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include "nav2_core/planner_exceptions.hpp" #include "nav2_theta_star_planner/theta_star.hpp" namespace theta_star @@ -26,6 +27,7 @@ ThetaStar::ThetaStar() allow_unknown_(true), size_x_(0), size_y_(0), + terminal_checking_interval_(5000), index_generated_(0) { exp_node = new tree_node; @@ -43,7 +45,7 @@ void ThetaStar::setStartAndGoal( dst_ = {static_cast(d[0]), static_cast(d[1])}; } -bool ThetaStar::generatePath(std::vector & raw_path) +bool ThetaStar::generatePath(std::vector & raw_path, std::function cancel_checker) { resetContainers(); addToNodesData(index_generated_); @@ -60,6 +62,11 @@ bool ThetaStar::generatePath(std::vector & raw_path) while (!queue_.empty()) { nodes_opened++; + if (nodes_opened % terminal_checking_interval_ == 0 && cancel_checker()) { + clearQueue(); + throw nav2_core::PlannerCancelled("Planner was canceled"); + } + if (isGoal(*curr_data)) { break; } diff --git a/nav2_theta_star_planner/src/theta_star_planner.cpp b/nav2_theta_star_planner/src/theta_star_planner.cpp index ca9391111b..61064efbf4 100644 --- a/nav2_theta_star_planner/src/theta_star_planner.cpp +++ b/nav2_theta_star_planner/src/theta_star_planner.cpp @@ -59,6 +59,10 @@ void ThetaStarPlanner::configure( planner_->w_heuristic_cost_ = planner_->w_euc_cost_ < 1.0 ? planner_->w_euc_cost_ : 1.0; + nav2_util::declare_parameter_if_not_declared( + node, name_ + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); + node->get_parameter(name_ + ".terminal_checking_interval", planner_->terminal_checking_interval_); + nav2_util::declare_parameter_if_not_declared( node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false)); node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_); @@ -86,7 +90,8 @@ void ThetaStarPlanner::deactivate() nav_msgs::msg::Path ThetaStarPlanner::createPlan( const geometry_msgs::msg::PoseStamped & start, - const geometry_msgs::msg::PoseStamped & goal) + const geometry_msgs::msg::PoseStamped & goal, + std::function cancel_checker) { nav_msgs::msg::Path global_path; auto start_time = std::chrono::steady_clock::now(); @@ -140,7 +145,7 @@ nav_msgs::msg::Path ThetaStarPlanner::createPlan( RCLCPP_DEBUG( logger_, "Got the src and dst... (%i, %i) && (%i, %i)", planner_->src_.x, planner_->src_.y, planner_->dst_.x, planner_->dst_.y); - getPlan(global_path); + getPlan(global_path, cancel_checker); // check if a plan is generated size_t plan_size = global_path.poses.size(); if (plan_size > 0) { @@ -173,13 +178,15 @@ nav_msgs::msg::Path ThetaStarPlanner::createPlan( return global_path; } -void ThetaStarPlanner::getPlan(nav_msgs::msg::Path & global_path) +void ThetaStarPlanner::getPlan( + nav_msgs::msg::Path & global_path, + std::function cancel_checker) { std::vector path; if (planner_->isUnsafeToPlan()) { global_path.poses.clear(); throw nav2_core::PlannerException("Either of the start or goal pose are an obstacle! "); - } else if (planner_->generatePath(path)) { + } else if (planner_->generatePath(path, cancel_checker)) { global_path = linearInterpolation(path, planner_->costmap_->getResolution()); } else { global_path.poses.clear(); @@ -229,6 +236,9 @@ ThetaStarPlanner::dynamicParametersCallback(std::vector param if (name == name_ + ".how_many_corners") { planner_->how_many_corners_ = parameter.as_int(); } + if (name == name_ + ".terminal_checking_interval") { + planner_->terminal_checking_interval_ = parameter.as_int(); + } } else if (type == ParameterType::PARAMETER_DOUBLE) { if (name == name_ + ".w_euc_cost") { planner_->w_euc_cost_ = parameter.as_double(); diff --git a/nav2_theta_star_planner/test/test_theta_star.cpp b/nav2_theta_star_planner/test/test_theta_star.cpp index 0476290f93..a8db0ddbfe 100644 --- a/nav2_theta_star_planner/test/test_theta_star.cpp +++ b/nav2_theta_star_planner/test/test_theta_star.cpp @@ -60,10 +60,12 @@ class test_theta_star : public theta_star::ThetaStar void uresetContainers() {nodes_data_.clear(); resetContainers();} - bool runAlgo(std::vector & path) + bool runAlgo( + std::vector & path, + std::function cancel_checker = [] () {return false;}) { if (!isUnsafeToPlan()) { - return generatePath(path); + return generatePath(path, cancel_checker); } return false; } @@ -162,7 +164,11 @@ TEST(ThetaStarPlanner, test_theta_star_planner) { planner_2d->configure(life_node, "test", nullptr, costmap_ros); planner_2d->activate(); - nav_msgs::msg::Path path = planner_2d->createPlan(start, goal); + auto dummy_cancel_checker = []() { + return false; + }; + + nav_msgs::msg::Path path = planner_2d->createPlan(start, goal, dummy_cancel_checker); EXPECT_GT(static_cast(path.poses.size()), 0); // test if the goal is unsafe @@ -174,7 +180,7 @@ TEST(ThetaStarPlanner, test_theta_star_planner) { goal.pose.position.x = 1.0; goal.pose.position.y = 1.0; - EXPECT_THROW(planner_2d->createPlan(start, goal), nav2_core::GoalOccupied); + EXPECT_THROW(planner_2d->createPlan(start, goal, dummy_cancel_checker), nav2_core::GoalOccupied); planner_2d->deactivate(); planner_2d->cleanup(); @@ -212,7 +218,8 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure) rclcpp::Parameter("test.w_euc_cost", 1.0), rclcpp::Parameter("test.w_traversal_cost", 2.0), rclcpp::Parameter("test.use_final_approach_orientation", false), - rclcpp::Parameter("test.allow_unknown", false)}); + rclcpp::Parameter("test.allow_unknown", false), + rclcpp::Parameter("test.terminal_checking_interval", 100)}); rclcpp::spin_until_future_complete( life_node->get_node_base_interface(), @@ -225,6 +232,7 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure) EXPECT_EQ(life_node->get_parameter("test.w_traversal_cost").as_double(), 2.0); EXPECT_EQ(life_node->get_parameter("test.use_final_approach_orientation").as_bool(), false); EXPECT_EQ(life_node->get_parameter("test.allow_unknown").as_bool(), false); + EXPECT_EQ(life_node->get_parameter("test.terminal_checking_interval").as_int(), 100); rclcpp::spin_until_future_complete( life_node->get_node_base_interface(),