Nav2 Navigation Stack - humble  humble
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 "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"
36 
37 using rcl_interfaces::msg::ParameterType;
38 
39 namespace nav2_theta_star_planner
40 {
41 
43 {
44 public:
45  void configure(
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;
49 
50  void cleanup() override;
51 
52  void activate() override;
53 
54  void deactivate() override;
55 
56  nav_msgs::msg::Path createPlan(
57  const geometry_msgs::msg::PoseStamped & start,
58  const geometry_msgs::msg::PoseStamped & goal) override;
59 
60 protected:
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_;
66 
67  // parent node weak ptr
68  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_;
69 
70  std::unique_ptr<theta_star::ThetaStar> planner_;
71 
72  // Dynamic parameters handler
73  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
74 
75 
80  void getPlan(nav_msgs::msg::Path & global_path);
81 
88  static nav_msgs::msg::Path linearInterpolation(
89  const std::vector<coordsW> & raw_path,
90  const double & dist_bw_points);
91 
96  rcl_interfaces::msg::SetParametersResult
97  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
98 };
99 } // namespace nav2_theta_star_planner
100 
101 #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 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.