Nav2 Navigation Stack - jazzy  jazzy
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_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
16 #define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <memory>
21 #include <algorithm>
22 #include <mutex>
23 
24 #include "rclcpp/rclcpp.hpp"
25 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
26 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
27 #include "nav2_util/odometry_utils.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_core/controller_exceptions.hpp"
30 #include "geometry_msgs/msg/pose2_d.hpp"
31 
32 namespace nav2_regulated_pure_pursuit_controller
33 {
34 
40 {
41 public:
46  tf2::Duration transform_tolerance,
47  std::shared_ptr<tf2_ros::Buffer> tf,
48  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
49 
53  ~PathHandler() = default;
54 
64  nav_msgs::msg::Path transformGlobalPlan(
65  const geometry_msgs::msg::PoseStamped & pose,
66  double max_robot_pose_search_dist, bool reject_unit_path = false);
67 
75  bool transformPose(
76  const std::string frame,
77  const geometry_msgs::msg::PoseStamped & in_pose,
78  geometry_msgs::msg::PoseStamped & out_pose) const;
79 
80  void setPlan(const nav_msgs::msg::Path & path) {global_plan_ = path;}
81 
82  nav_msgs::msg::Path getPlan() {return global_plan_;}
83 
84 protected:
89  double getCostmapMaxExtent() const;
90 
91  rclcpp::Logger logger_ {rclcpp::get_logger("RPPPathHandler")};
92  tf2::Duration transform_tolerance_;
93  std::shared_ptr<tf2_ros::Buffer> tf_;
94  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
95  nav_msgs::msg::Path global_plan_;
96 };
97 
98 } // namespace nav2_regulated_pure_pursuit_controller
99 
100 #endif // NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
Handles input paths to transform them to local frames required.
bool transformPose(const std::string frame, const geometry_msgs::msg::PoseStamped &in_pose, geometry_msgs::msg::PoseStamped &out_pose) const
Transform a pose to another frame.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist, bool reject_unit_path=false)
Transforms global plan into same frame as pose and clips poses ineligible for lookaheadPoint Points i...
PathHandler(tf2::Duration transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_regulated_pure_pursuit_controller::PathHandler.
~PathHandler()=default
Destrructor for nav2_regulated_pure_pursuit_controller::PathHandler.