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 "nav_msgs/msg/path.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_util/lifecycle_node.hpp"
31 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
32 #include "nav2_costmap_2d/cost_values.hpp"
33 #include "nav2_util/node_utils.hpp"
34 #include "nav2_theta_star_planner/theta_star.hpp"
35 #include "nav2_util/geometry_utils.hpp"
37 using rcl_interfaces::msg::ParameterType;
39 namespace nav2_theta_star_planner
46 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
47 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
48 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
57 const geometry_msgs::msg::PoseStamped & start,
58 const geometry_msgs::msg::PoseStamped & goal)
override;
61 std::shared_ptr<tf2_ros::Buffer> tf_;
62 rclcpp::Clock::SharedPtr clock_;
63 rclcpp::Logger logger_{rclcpp::get_logger(
"ThetaStarPlanner")};
64 std::string global_frame_, name_;
65 bool use_final_approach_orientation_;
68 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_;
70 std::unique_ptr<theta_star::ThetaStar> planner_;
73 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
80 void getPlan(nav_msgs::msg::Path & global_path);
89 const std::vector<coordsW> & raw_path,
90 const double & dist_bw_points);
96 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
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Method create the plan from a starting and ending goal.
void cleanup() override
Method to cleanup resources used on shutdown.
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 getPlan(nav_msgs::msg::Path &global_path)
the function responsible for calling the algorithm and retrieving a path from it
void activate() override
Method to active planner and any threads involved in execution.