15 #ifndef ERROR_CODES__PLANNER__PLANNER_ERROR_PLUGIN_HPP_
16 #define ERROR_CODES__PLANNER__PLANNER_ERROR_PLUGIN_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "geometry_msgs/msg/point.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_core/global_planner.hpp"
26 #include "nav_msgs/msg/path.hpp"
27 #include "nav2_util/robot_utils.hpp"
28 #include "nav2_util/lifecycle_node.hpp"
29 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
30 #include "nav2_core/planner_exceptions.hpp"
32 namespace nav2_system_tests
42 const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
43 std::string, std::shared_ptr<tf2_ros::Buffer>,
44 std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)
override {}
53 const geometry_msgs::msg::PoseStamped &,
54 const geometry_msgs::msg::PoseStamped &,
55 std::function<
bool()>)
override
63 nav_msgs::msg::Path createPlan(
64 const geometry_msgs::msg::PoseStamped &,
65 const geometry_msgs::msg::PoseStamped &,
66 std::function<
bool()>)
override
74 nav_msgs::msg::Path createPlan(
75 const geometry_msgs::msg::PoseStamped &,
76 const geometry_msgs::msg::PoseStamped &,
77 std::function<
bool()>)
override
85 nav_msgs::msg::Path createPlan(
86 const geometry_msgs::msg::PoseStamped &,
87 const geometry_msgs::msg::PoseStamped &,
88 std::function<
bool()>)
override
96 nav_msgs::msg::Path createPlan(
97 const geometry_msgs::msg::PoseStamped &,
98 const geometry_msgs::msg::PoseStamped &,
99 std::function<
bool()>)
override
107 nav_msgs::msg::Path createPlan(
108 const geometry_msgs::msg::PoseStamped &,
109 const geometry_msgs::msg::PoseStamped &,
110 std::function<
bool()>)
override
112 return nav_msgs::msg::Path();
119 nav_msgs::msg::Path createPlan(
120 const geometry_msgs::msg::PoseStamped &,
121 const geometry_msgs::msg::PoseStamped &,
122 std::function<
bool()>)
override
130 nav_msgs::msg::Path createPlan(
131 const geometry_msgs::msg::PoseStamped &,
132 const geometry_msgs::msg::PoseStamped &,
133 std::function<
bool()>)
override
141 nav_msgs::msg::Path createPlan(
142 const geometry_msgs::msg::PoseStamped &,
143 const geometry_msgs::msg::PoseStamped &,
144 std::function<
bool()>)
override
152 nav_msgs::msg::Path createPlan(
153 const geometry_msgs::msg::PoseStamped &,
154 const geometry_msgs::msg::PoseStamped &,
155 std::function<
bool()> cancel_checker)
override
157 auto start_time = std::chrono::steady_clock::now();
158 while (rclcpp::ok() &&
159 std::chrono::steady_clock::now() - start_time < std::chrono::seconds(5))
161 if (cancel_checker()) {
164 rclcpp::sleep_for(std::chrono::milliseconds(100));
Abstract interface for global planners to adhere to with pluginlib.
void cleanup() override
Method to cleanup resources used on shutdown.
void deactivate() override
Method to deactive planner and any threads involved in execution.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, std::function< bool()>) override
Method create the plan from a starting and ending goal.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &, std::string, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >) override
void activate() override
Method to active planner and any threads involved in execution.