Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
path_handler.hpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 // Copyright (c) 2023 Dexory
3 // Copyright (c) 2023 Open Navigation LLC
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__PATH_HANDLER_HPP_
18 #define NAV2_MPPI_CONTROLLER__TOOLS__PATH_HANDLER_HPP_
19 
20 #include <vector>
21 #include <utility>
22 #include <string>
23 #include <memory>
24 
25 #include "rclcpp_lifecycle/lifecycle_node.hpp"
26 #include "tf2_ros/buffer.h"
27 #include "geometry_msgs/msg/pose_stamped.hpp"
28 #include "nav_msgs/msg/path.hpp"
29 #include "builtin_interfaces/msg/time.hpp"
30 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
31 #include "nav2_util/geometry_utils.hpp"
32 #include "nav2_core/controller_exceptions.hpp"
33 
34 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
35 
36 namespace mppi
37 {
38 
39 using PathIterator = std::vector<geometry_msgs::msg::PoseStamped>::iterator;
40 using PathRange = std::pair<PathIterator, PathIterator>;
41 
48 {
49 public:
53  PathHandler() = default;
54 
58  ~PathHandler() = default;
59 
68  void initialize(
69  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
70  std::shared_ptr<nav2_costmap_2d::Costmap2DROS>,
71  std::shared_ptr<tf2_ros::Buffer>, ParametersHandler *);
72 
77  void setPath(const nav_msgs::msg::Path & plan);
78 
83  nav_msgs::msg::Path & getPath();
84 
91  nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped & robot_pose);
92 
98  geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time & stamp);
99 
100 protected:
108  bool transformPose(
109  const std::string & frame, const geometry_msgs::msg::PoseStamped & in_pose,
110  geometry_msgs::msg::PoseStamped & out_pose) const;
111 
116  double getMaxCostmapDist();
117 
123  geometry_msgs::msg::PoseStamped
124  transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped & pose);
125 
132  std::pair<nav_msgs::msg::Path, PathIterator> getGlobalPlanConsideringBoundsInCostmapFrame(
133  const geometry_msgs::msg::PoseStamped & global_pose);
134 
140  void prunePlan(nav_msgs::msg::Path & plan, const PathIterator end);
141 
147  bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose);
148 
149  std::string name_;
150  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_;
151  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
152  ParametersHandler * parameters_handler_;
153 
154  nav_msgs::msg::Path global_plan_;
155  nav_msgs::msg::Path global_plan_up_to_inversion_;
156  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
157 
158  double max_robot_pose_search_dist_{0};
159  double prune_distance_{0};
160  double transform_tolerance_{0};
161  float inversion_xy_tolerance_{0.2};
162  float inversion_yaw_tolerance{0.4};
163  bool enforce_path_inversion_{false};
164  unsigned int inversion_locale_{0u};
165 };
166 } // namespace mppi
167 
168 #endif // NAV2_MPPI_CONTROLLER__TOOLS__PATH_HANDLER_HPP_
Handles getting parameters and dynamic parameter changes.
Manager of incoming reference paths for transformation and processing.
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped &robot_pose)
Check if the robot pose is within the set inversion tolerances.
std::pair< nav_msgs::msg::Path, PathIterator > getGlobalPlanConsideringBoundsInCostmapFrame(const geometry_msgs::msg::PoseStamped &global_pose)
Get global plan within window of the local costmap size.
nav_msgs::msg::Path & getPath()
Get reference path.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
double getMaxCostmapDist()
Get largest dimension of costmap (radially)
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
PathHandler()=default
Constructor for mppi::PathHandler.
~PathHandler()=default
Destructor for mppi::PathHandler.
void prunePlan(nav_msgs::msg::Path &plan, const PathIterator end)
Prune a path to only interesting portions.
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.
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, std::shared_ptr< tf2_ros::Buffer >, ParametersHandler *)
Initialize path handler on bringup.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
geometry_msgs::msg::PoseStamped transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped &pose)
Transform a pose to the global reference frame.