diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp index fe0f0aacc75..698d7b479d8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp @@ -16,6 +16,7 @@ #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_ACTION_HPP_ #include +#include #include "nav2_msgs/action/compute_path_to_pose.hpp" #include "nav_msgs/msg/path.hpp" @@ -94,6 +95,9 @@ class ComputePathToPoseAction : public BtActionNode>( + "viapoints", + "A list of intermediate viapoints (excluding goal) to consider for planning"), BT::InputPort( "use_start", "For using or not using (i.e. ignoring) the provided start pose"), BT::InputPort( diff --git a/nav2_behavior_tree/nav2_tree_nodes.xml b/nav2_behavior_tree/nav2_tree_nodes.xml index 40d8c10b54b..a26a64e34c7 100644 --- a/nav2_behavior_tree/nav2_tree_nodes.xml +++ b/nav2_behavior_tree/nav2_tree_nodes.xml @@ -96,6 +96,7 @@ Destination to plan to Use as the planner start pose instead of the current robot pose, if use_start is not false (i.e. not provided or set to true) + A vector of intermediate viapoints (excluding goal) to consider for planning For using or not using (i.e. ignoring) the provided start pose Mapped name to the planner plugin type to use Server name diff --git a/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp b/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp index 3ff618a007b..dcd2fa2c587 100644 --- a/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp +++ b/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp @@ -33,6 +33,11 @@ void ComputePathToPoseAction::on_tick() getInput("goal", goal_.goal); getInput("planner_id", goal_.planner_id); + // use waypoints if available + if (!getInput("viapoints", goal_.viapoints)) { + goal_.viapoints = std::vector(); + } + // if "use_start" is provided try to enforce it (true or false), but we cannot enforce true if // start is not provided goal_.use_start = false; diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index fa63d2e519e..1af70e3efe7 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -17,6 +17,7 @@ #include #include +#include #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "tf2_ros/buffer.hpp" #include "nav_msgs/msg/path.hpp" @@ -67,15 +68,17 @@ class GlobalPlanner virtual void deactivate() = 0; /** - * @brief Method create the plan from a starting and ending goal. + * @brief Method to create the plan from a starting pose, a goal pose, and intermediate viapoints. * @param start The starting pose of the robot * @param goal The goal pose of the robot + * @param viapoints The intermediate viapoints for 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, + const std::vector & viapoints, std::function cancel_checker) = 0; }; diff --git a/nav2_msgs/action/ComputePathToPose.action b/nav2_msgs/action/ComputePathToPose.action index 572a9b5b5a5..ff3e02aeffe 100644 --- a/nav2_msgs/action/ComputePathToPose.action +++ b/nav2_msgs/action/ComputePathToPose.action @@ -1,6 +1,7 @@ #goal definition geometry_msgs/PoseStamped goal geometry_msgs/PoseStamped start +geometry_msgs/PoseStamped[] viapoints string planner_id bool use_start # If false, use current robot pose as path start, if true, use start above instead --- 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 873076b01ba..ca1f361f46a 100644 --- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp +++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp @@ -88,6 +88,7 @@ class NavfnPlanner : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) override; protected: diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index ddbaeb3537c..1d82cc0f1c5 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -120,11 +120,18 @@ NavfnPlanner::cleanup() nav_msgs::msg::Path NavfnPlanner::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) { #ifdef BENCHMARK_TESTING steady_clock::time_point a = steady_clock::now(); #endif + + if (!viapoints.empty()) { + RCLCPP_WARN(logger_, "Received %zu viapoints, but this planner ignores them", + viapoints.size()); + } + std::lock_guard lock_reinit(param_handler_->getMutex()); unsigned int mx_start, my_start, mx_goal, my_goal; if (!costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start)) { diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp index 1fe05393e28..04c7f91399f 100644 --- a/nav2_planner/include/nav2_planner/planner_server.hpp +++ b/nav2_planner/include/nav2_planner/planner_server.hpp @@ -76,6 +76,7 @@ class PlannerServer : public nav2::LifecycleNode nav_msgs::msg::Path getPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, const std::string & planner_id, std::function cancel_checker); diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 45b5a7daeb3..d5c5470f48e 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -394,8 +394,9 @@ void PlannerServer::computePlanThroughPoses() // Get plan from start -> goal nav_msgs::msg::Path curr_path; + std::vector viapoints; try { - curr_path = getPlan(curr_start, curr_goal, goal->planner_id, cancel_checker); + curr_path = getPlan(curr_start, curr_goal, viapoints, goal->planner_id, cancel_checker); } catch (nav2_core::PlannerException & ex) { if (i == 0 || !params_->partial_plan_allowed) { throw; @@ -546,7 +547,7 @@ PlannerServer::computePlan() return action_server_pose_->is_cancel_requested(); }; - result->path = getPlan(start, goal_pose, goal->planner_id, cancel_checker); + result->path = getPlan(start, goal_pose, goal->viapoints, 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"); @@ -615,6 +616,7 @@ nav_msgs::msg::Path PlannerServer::getPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, const std::string & planner_id, std::function cancel_checker) { @@ -624,14 +626,15 @@ PlannerServer::getPlan( goal.pose.position.x, goal.pose.position.y); if (planners_.find(planner_id) != planners_.end()) { - return planners_[planner_id]->createPlan(start, goal, cancel_checker); + return planners_[planner_id]->createPlan(start, goal, viapoints, 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, cancel_checker); + return planners_[planners_.begin()->first]->createPlan(start, goal, viapoints, + cancel_checker); } else { RCLCPP_ERROR( get_logger(), "planner %s is not a valid planner. " 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 81e93b83217..5edf22acbf6 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 @@ -88,6 +88,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) override; protected: 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 cbd1d0239fc..9785410ad0c 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 @@ -87,6 +87,7 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) override; protected: 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 26d479b713b..76e65be7137 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 @@ -86,6 +86,7 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) override; protected: diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index e27a6a58307..a62641da414 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -194,8 +194,14 @@ void SmacPlanner2D::cleanup() nav_msgs::msg::Path SmacPlanner2D::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) { + if (!viapoints.empty()) { + RCLCPP_WARN(_logger, "Received %zu viapoints, but this planner ignores them", + viapoints.size()); + } + std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 49053d66281..c369bfceb37 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -339,8 +339,14 @@ void SmacPlannerHybrid::cleanup() nav_msgs::msg::Path SmacPlannerHybrid::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) { + if (!viapoints.empty()) { + RCLCPP_WARN(_logger, "Received %zu viapoints, but this planner ignores them", + viapoints.size()); + } + std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 585717229ed..64360a8be64 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -300,8 +300,14 @@ void SmacPlannerLattice::cleanup() nav_msgs::msg::Path SmacPlannerLattice::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) { + if (!viapoints.empty()) { + RCLCPP_WARN(_logger, "Received %zu viapoints, but this planner ignores them", + viapoints.size()); + } + std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index 06f4e7e0bff..d1a00aa7454 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -56,7 +56,7 @@ TEST(SmacTest, test_smac_2d) { return false; }; - geometry_msgs::msg::PoseStamped start, goal; + geometry_msgs::msg::PoseStamped start, goal, viapoint; start.pose.position.x = 0.0; start.pose.position.y = 0.0; start.pose.orientation.w = 1.0; @@ -64,11 +64,16 @@ TEST(SmacTest, test_smac_2d) { goal.pose.position.x = 7.0; goal.pose.position.y = 0.0; goal.pose.orientation.w = 1.0; + // viapoint = start; + goal.pose.position.x = 3.5; + goal.pose.position.y = 0.0; + goal.pose.orientation.w = 1.0; + std::vector viapoints{viapoint}; auto planner_2d = std::make_unique(); planner_2d->configure(node2D, "test", nullptr, costmap_ros); planner_2d->activate(); try { - planner_2d->createPlan(start, goal, dummy_cancel_checker); + planner_2d->createPlan(start, goal, viapoints, dummy_cancel_checker); } catch (...) { } @@ -76,7 +81,7 @@ TEST(SmacTest, test_smac_2d) { goal.pose.position.x = 0.01; goal.pose.position.y = 0.01; - nav_msgs::msg::Path plan = planner_2d->createPlan(start, goal, dummy_cancel_checker); + nav_msgs::msg::Path plan = planner_2d->createPlan(start, goal, viapoints, dummy_cancel_checker); EXPECT_EQ(plan.poses.size(), 1); // single point path planner_2d->deactivate(); diff --git a/nav2_smac_planner/test/test_smac_hybrid.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp index 33eb6f12729..6497677243d 100644 --- a/nav2_smac_planner/test/test_smac_hybrid.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -109,13 +109,18 @@ TEST(SmacTest, test_smac_se2) return false; }; - geometry_msgs::msg::PoseStamped start, goal; + std::vector no_viapoints{}; + geometry_msgs::msg::PoseStamped start, goal, viapoint; start.pose.position.x = 0.0; start.pose.position.y = 0.0; start.pose.orientation.w = 1.0; goal.pose.position.x = 1.0; goal.pose.position.y = 1.0; goal.pose.orientation.w = 1.0; + viapoint.pose.position.x = 0.5; + viapoint.pose.position.y = 0.5; + viapoint.pose.orientation.w = 1.0; + std::vector viapoints{viapoint}; auto planner = std::make_unique(); // invalid goal heading mode @@ -160,7 +165,7 @@ TEST(SmacTest, test_smac_se2) planner->activate(); try { - planner->createPlan(start, goal, dummy_cancel_checker); + planner->createPlan(start, goal, viapoints, dummy_cancel_checker); } catch (...) { } @@ -186,7 +191,8 @@ TEST(SmacTest, test_smac_se2) goal.pose.position.x = 0.01; goal.pose.position.y = 0.01; - nav_msgs::msg::Path plan = planner->createPlan(start, goal, dummy_cancel_checker); + nav_msgs::msg::Path plan = planner->createPlan( + start, goal, no_viapoints, dummy_cancel_checker); EXPECT_EQ(plan.poses.size(), 1); // single point path auto rec_param = std::make_shared( @@ -200,7 +206,8 @@ TEST(SmacTest, test_smac_se2) executor.spin_until_future_complete(results); goal.pose.position.x = 4.0; goal.pose.position.y = 4.0; - EXPECT_THROW(planner->createPlan(start, goal, dummy_cancel_checker), std::runtime_error); + EXPECT_THROW(planner->createPlan( + start, goal, no_viapoints, dummy_cancel_checker), std::runtime_error); planner->deactivate(); planner->cleanup(); diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index 467e0f009b6..612b47a0b66 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -121,13 +121,18 @@ TEST(SmacTest, test_smac_lattice) return false; }; - geometry_msgs::msg::PoseStamped start, goal; + std::vector no_viapoints{}; + geometry_msgs::msg::PoseStamped start, goal, viapoint; start.pose.position.x = 0.0; start.pose.position.y = 0.0; start.pose.orientation.w = 1.0; goal.pose.position.x = 1.0; goal.pose.position.y = 1.0; goal.pose.orientation.w = 1.0; + viapoint.pose.position.x = 0.5; + viapoint.pose.position.y = 0.5; + viapoint.pose.orientation.w = 1.0; + std::vector viapoints{viapoint}; auto planner = std::make_unique(); try { // invalid goal heading mode @@ -165,7 +170,7 @@ TEST(SmacTest, test_smac_lattice) planner->activate(); try { - planner->createPlan(start, goal, dummy_cancel_checker); + planner->createPlan(start, goal, viapoints, dummy_cancel_checker); } catch (...) { } @@ -192,7 +197,7 @@ TEST(SmacTest, test_smac_lattice) goal.pose.position.x = 0.01; goal.pose.position.y = 0.01; - nav_msgs::msg::Path plan = planner->createPlan(start, goal, dummy_cancel_checker); + nav_msgs::msg::Path plan = planner->createPlan(start, goal, no_viapoints, dummy_cancel_checker); EXPECT_EQ(plan.poses.size(), 1); // single point path auto rec_param = std::make_shared( @@ -206,7 +211,8 @@ TEST(SmacTest, test_smac_lattice) executor.spin_until_future_complete(results); goal.pose.position.x = 4.0; goal.pose.position.y = 4.0; - EXPECT_THROW(planner->createPlan(start, goal, dummy_cancel_checker), std::runtime_error); + EXPECT_THROW(planner->createPlan( + start, goal, no_viapoints, dummy_cancel_checker), std::runtime_error); planner->deactivate(); planner->cleanup(); 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 0e6b31c7af0..925b9318a56 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 @@ -17,6 +17,7 @@ #include #include +#include #include "rclcpp/rclcpp.hpp" #include "geometry_msgs/msg/point.hpp" @@ -52,6 +53,7 @@ class UnknownErrorPlanner : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::PlannerException("Unknown Error"); @@ -63,6 +65,7 @@ class StartOccupiedErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::StartOccupied("Start Occupied"); @@ -74,6 +77,7 @@ class GoalOccupiedErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::GoalOccupied("Goal occupied"); @@ -85,6 +89,7 @@ class StartOutsideMapErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::StartOutsideMapBounds("Start OutsideMapBounds"); @@ -96,6 +101,7 @@ class GoalOutsideMapErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::GoalOutsideMapBounds("Goal outside map bounds"); @@ -107,6 +113,7 @@ class NoValidPathErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { return nav_msgs::msg::Path(); @@ -119,6 +126,7 @@ class TimedOutErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::PlannerTimedOut("Planner Timed Out"); @@ -130,6 +138,7 @@ class TFErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::PlannerTFError("TF Error"); @@ -141,6 +150,7 @@ class NoViapointsGivenErrorPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function) override { throw nav2_core::NoViapointsGiven("No Via points given"); @@ -152,6 +162,7 @@ class CancelledPlanner : public UnknownErrorPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, + const std::vector &, std::function cancel_checker) override { auto start_time = std::chrono::steady_clock::now(); diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index 5ce88310b45..27c4ca12a12 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include "nav2_ros_common/lifecycle_node.hpp" @@ -85,7 +86,8 @@ class NavFnPlannerTester : public nav2_planner::PlannerServer } try { auto dummy_cancel_checker = []() {return false;}; - path = planners_["GridBased"]->createPlan(start, goal, dummy_cancel_checker); + std::vector viapoints{start}; + path = planners_["GridBased"]->createPlan(start, goal, viapoints, 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 76d6bf9a74a..6abec7058ad 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -19,6 +19,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/path.hpp" +#include "nav_msgs/msg/goals.hpp" #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" #include "nav2_util/geometry_utils.hpp" @@ -47,6 +48,7 @@ void testSmallPathValidityAndOrientation(std::string plugin, double length) geometry_msgs::msg::PoseStamped start; geometry_msgs::msg::PoseStamped goal; + std::vector no_viapoints; start.pose.position.x = 0.5; start.pose.position.y = 0.5; @@ -62,7 +64,7 @@ void testSmallPathValidityAndOrientation(std::string plugin, double length) // Test without use_final_approach_orientation // expecting end path pose orientation to be equal to goal orientation - auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker); + auto path = obj->getPlan(start, goal, no_viapoints, "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); @@ -84,6 +86,7 @@ void testSmallPathValidityAndNoOrientation(std::string plugin, double length) geometry_msgs::msg::PoseStamped start; geometry_msgs::msg::PoseStamped goal; + std::vector no_viapoints; start.pose.position.x = 0.5; start.pose.position.y = 0.5; @@ -97,7 +100,7 @@ void testSmallPathValidityAndNoOrientation(std::string plugin, double length) auto dummy_cancel_checker = []() {return false;}; - auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker); + auto path = obj->getPlan(start, goal, no_viapoints, "GridBased", dummy_cancel_checker); EXPECT_GT((int)path.poses.size(), 0); int path_size = path.poses.size(); @@ -128,6 +131,7 @@ void testCancel(std::string plugin) geometry_msgs::msg::PoseStamped start; geometry_msgs::msg::PoseStamped goal; + std::vector no_viapoints; start.pose.position.x = 0.0; start.pose.position.y = 0.0; @@ -142,7 +146,7 @@ void testCancel(std::string plugin) auto always_cancelled = []() {return true;}; EXPECT_THROW( - obj->getPlan(start, goal, "GridBased", always_cancelled), + obj->getPlan(start, goal, no_viapoints, "GridBased", always_cancelled), nav2_core::PlannerCancelled); obj->onCleanup(state); obj.reset(); @@ -159,16 +163,17 @@ TEST(testPluginMap, Failures) geometry_msgs::msg::PoseStamped start; geometry_msgs::msg::PoseStamped goal; + std::vector no_viapoints; std::string plugin_fake = "fake"; std::string plugin_none = ""; auto dummy_cancel_checker = []() {return false;}; - auto path = obj->getPlan(start, goal, plugin_none, dummy_cancel_checker); + auto path = obj->getPlan(start, goal, no_viapoints, plugin_none, dummy_cancel_checker); EXPECT_EQ(path.header.frame_id, std::string("map")); try { - path = obj->getPlan(start, goal, plugin_fake, dummy_cancel_checker); + path = obj->getPlan(start, goal, no_viapoints, 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")); 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 2bb1837f2c1..3c7376c340a 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 @@ -65,6 +65,7 @@ class ThetaStarPlanner : public nav2_core::GlobalPlanner nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) override; protected: diff --git a/nav2_theta_star_planner/src/theta_star_planner.cpp b/nav2_theta_star_planner/src/theta_star_planner.cpp index 915ad05a549..5e3f63660c3 100644 --- a/nav2_theta_star_planner/src/theta_star_planner.cpp +++ b/nav2_theta_star_planner/src/theta_star_planner.cpp @@ -68,8 +68,14 @@ void ThetaStarPlanner::deactivate() nav_msgs::msg::Path ThetaStarPlanner::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal, + const std::vector & viapoints, std::function cancel_checker) { + if (!viapoints.empty()) { + RCLCPP_WARN(logger_, "Received %zu viapoints, but this planner ignores them", + viapoints.size()); + } + std::lock_guard lock_reinit(param_handler_->getMutex()); nav_msgs::msg::Path global_path; auto start_time = std::chrono::steady_clock::now(); diff --git a/nav2_theta_star_planner/test/test_theta_star.cpp b/nav2_theta_star_planner/test/test_theta_star.cpp index e411c99fb57..7a9754a37c4 100644 --- a/nav2_theta_star_planner/test/test_theta_star.cpp +++ b/nav2_theta_star_planner/test/test_theta_star.cpp @@ -155,11 +155,12 @@ TEST(ThetaStarPlanner, test_theta_star_planner) { std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); - geometry_msgs::msg::PoseStamped start, goal; + geometry_msgs::msg::PoseStamped start, goal, viapoint; start.pose.position.x = 0.0; start.pose.position.y = 0.0; start.pose.orientation.w = 1.0; goal = start; + viapoint = start; auto planner_2d = std::make_unique(); planner_2d->configure(life_node, "test", nullptr, costmap_ros); planner_2d->activate(); @@ -168,7 +169,9 @@ TEST(ThetaStarPlanner, test_theta_star_planner) { return false; }; - nav_msgs::msg::Path path = planner_2d->createPlan(start, goal, dummy_cancel_checker); + std::vector viapoints{viapoint}; + nav_msgs::msg::Path path = planner_2d->createPlan( + start, goal, viapoints, dummy_cancel_checker); EXPECT_GT(static_cast(path.poses.size()), 0); // test if the goal is unsafe @@ -180,7 +183,8 @@ 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, dummy_cancel_checker), nav2_core::GoalOccupied); + EXPECT_THROW(planner_2d->createPlan(start, goal, viapoints, dummy_cancel_checker), + nav2_core::GoalOccupied); planner_2d->deactivate(); planner_2d->cleanup();