Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
theta_star_planner.hpp
1 // Copyright 2020 Anshumaan Singh
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_THETA_STAR_PLANNER__THETA_STAR_PLANNER_HPP_
16 #define NAV2_THETA_STAR_PLANNER__THETA_STAR_PLANNER_HPP_
17 
18 #include <iostream>
19 #include <cmath>
20 #include <string>
21 #include <chrono>
22 #include <queue>
23 #include <algorithm>
24 #include <memory>
25 #include <vector>
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"
37 
38 using rcl_interfaces::msg::ParameterType;
39 
40 namespace nav2_theta_star_planner
41 {
42 
44 {
45 public:
46  void configure(
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;
50 
51  void cleanup() override;
52 
53  void activate() override;
54 
55  void deactivate() override;
56 
64  nav_msgs::msg::Path createPlan(
65  const geometry_msgs::msg::PoseStamped & start,
66  const geometry_msgs::msg::PoseStamped & goal,
67  std::function<bool()> cancel_checker) override;
68 
69 protected:
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_;
75 
76  // parent node weak ptr
77  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_;
78 
79  std::unique_ptr<theta_star::ThetaStar> planner_;
80 
81  // Dynamic parameters handler
82  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
83 
84 
90  void getPlan(nav_msgs::msg::Path & global_path, std::function<bool()> cancel_checker);
91 
98  static nav_msgs::msg::Path linearInterpolation(
99  const std::vector<coordsW> & raw_path,
100  const double & dist_bw_points);
101 
106  rcl_interfaces::msg::SetParametersResult
107  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
108 };
109 } // namespace nav2_theta_star_planner
110 
111 #endif // NAV2_THETA_STAR_PLANNER__THETA_STAR_PLANNER_HPP_
Abstract interface for global planners to adhere to with pluginlib.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter 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 deactivate planner and any threads involved in execution.
void activate() override
Method to active planner and any threads involved in execution.