15 #ifndef NAV2_THETA_STAR_PLANNER__THETA_STAR_PLANNER_HPP_
16 #define NAV2_THETA_STAR_PLANNER__THETA_STAR_PLANNER_HPP_
26 #include "rclcpp/rclcpp.hpp"
27 #include "nav2_core/global_planner.hpp"
28 #include "nav2_core/planner_exceptions.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 #include "nav2_util/lifecycle_node.hpp"
32 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
33 #include "nav2_costmap_2d/cost_values.hpp"
34 #include "nav2_util/node_utils.hpp"
35 #include "nav2_theta_star_planner/theta_star.hpp"
36 #include "nav2_util/geometry_utils.hpp"
38 using rcl_interfaces::msg::ParameterType;
40 namespace nav2_theta_star_planner
47 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
48 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
49 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
65 const geometry_msgs::msg::PoseStamped & start,
66 const geometry_msgs::msg::PoseStamped & goal,
67 std::function<
bool()> cancel_checker)
override;
70 std::shared_ptr<tf2_ros::Buffer> tf_;
71 rclcpp::Clock::SharedPtr clock_;
72 rclcpp::Logger logger_{rclcpp::get_logger(
"ThetaStarPlanner")};
73 std::string global_frame_, name_;
74 bool use_final_approach_orientation_;
77 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_;
79 std::unique_ptr<theta_star::ThetaStar> planner_;
82 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
90 void getPlan(nav_msgs::msg::Path & global_path, std::function<
bool()> cancel_checker);
99 const std::vector<coordsW> & raw_path,
100 const double & dist_bw_points);
106 rcl_interfaces::msg::SetParametersResult
Abstract interface for global planners to adhere to with pluginlib.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
void getPlan(nav_msgs::msg::Path &global_path, std::function< bool()> cancel_checker)
the function responsible for calling the algorithm and retrieving a path from it
void cleanup() override
Method to cleanup resources used on shutdown.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
static nav_msgs::msg::Path linearInterpolation(const std::vector< coordsW > &raw_path, const double &dist_bw_points)
interpolates points between the consecutive waypoints of the path
void deactivate() override
Method to deactive planner and any threads involved in execution.
void activate() override
Method to active planner and any threads involved in execution.