Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
path_handler.hpp
1 // Copyright (c) 2022 Samsung Research America
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_GRACEFUL_CONTROLLER__PATH_HANDLER_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__PATH_HANDLER_HPP_
17 
18 #include <memory>
19 
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 #include "nav2_util/geometry_utils.hpp"
23 
24 namespace nav2_graceful_controller
25 {
26 
32 {
33 public:
38  tf2::Duration transform_tolerance,
39  std::shared_ptr<tf2_ros::Buffer> tf,
40  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
41 
45  ~PathHandler() = default;
46 
55  nav_msgs::msg::Path transformGlobalPlan(
56  const geometry_msgs::msg::PoseStamped & pose,
57  double max_robot_pose_search_dist);
58 
64  void setPlan(const nav_msgs::msg::Path & path);
65 
71  nav_msgs::msg::Path getPlan() {return global_plan_;}
72 
73 protected:
74  rclcpp::Duration transform_tolerance_{0, 0};
75  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
76  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
77  nav_msgs::msg::Path global_plan_;
78  rclcpp::Logger logger_ {rclcpp::get_logger("GracefulPathHandler")};
79 };
80 
81 } // namespace nav2_graceful_controller
82 
83 #endif // NAV2_GRACEFUL_CONTROLLER__PATH_HANDLER_HPP_
Handles input paths to transform them to local frames required.
nav_msgs::msg::Path getPlan()
Gets the global plan.
void setPlan(const nav_msgs::msg::Path &path)
Sets the global plan.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist)
Transforms global plan into same frame as pose and clips poses ineligible for motionTarget Points ine...
PathHandler(tf2::Duration transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_graceful_controller::PathHandler.
~PathHandler()=default
Destructor for nav2_graceful_controller::PathHandler.