Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
smac_planner_hybrid.hpp
1 // Copyright (c) 2020, 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. Reserved.
14 
15 #ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "nav2_smac_planner/a_star.hpp"
23 #include "nav2_smac_planner/smoother.hpp"
24 #include "nav2_smac_planner/utils.hpp"
25 #include "nav2_smac_planner/costmap_downsampler.hpp"
26 #include "nav_msgs/msg/occupancy_grid.hpp"
27 #include "nav2_core/global_planner.hpp"
28 #include "nav_msgs/msg/path.hpp"
29 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
30 #include "nav2_costmap_2d/costmap_2d.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "geometry_msgs/msg/pose_array.hpp"
33 #include "nav2_util/lifecycle_node.hpp"
34 #include "nav2_util/node_utils.hpp"
35 #include "tf2/utils.hpp"
36 
37 namespace nav2_smac_planner
38 {
39 
41 {
42 public:
47 
52 
60  void configure(
61  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
62  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
63  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
64 
68  void cleanup() override;
69 
73  void activate() override;
74 
78  void deactivate() override;
79 
87  nav_msgs::msg::Path createPlan(
88  const geometry_msgs::msg::PoseStamped & start,
89  const geometry_msgs::msg::PoseStamped & goal,
90  std::function<bool()> cancel_checker) override;
91 
92 protected:
97  rcl_interfaces::msg::SetParametersResult
98  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
99 
100  std::unique_ptr<AStarAlgorithm<NodeHybrid>> _a_star;
101  GridCollisionChecker _collision_checker;
102  std::unique_ptr<Smoother> _smoother;
103  rclcpp::Clock::SharedPtr _clock;
104  rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerHybrid")};
105  nav2_costmap_2d::Costmap2D * _costmap;
106  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> _costmap_ros;
107  std::unique_ptr<CostmapDownsampler> _costmap_downsampler;
108  std::string _global_frame, _name;
109  float _lookup_table_dim;
110  float _tolerance;
111  bool _downsample_costmap;
112  int _downsampling_factor;
113  double _angle_bin_size;
114  unsigned int _angle_quantizations;
115  bool _allow_unknown;
116  int _max_iterations;
117  int _max_on_approach_iterations;
118  int _terminal_checking_interval;
119  SearchInfo _search_info;
120  double _max_planning_time;
121  double _lookup_table_size;
122  double _minimum_turning_radius_global_coords;
123  bool _debug_visualizations;
124  std::string _motion_model_for_search;
125  MotionModel _motion_model;
126  GoalHeadingMode _goal_heading_mode;
127  int _coarse_search_resolution;
128  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
129  rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
130  _planned_footprints_publisher;
131  rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
132  _smoothed_footprints_publisher;
133  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr
134  _expansions_publisher;
135  std::mutex _mutex;
136  rclcpp_lifecycle::LifecycleNode::WeakPtr _node;
137 
138  // Dynamic parameters handler
139  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler;
140  std::shared_ptr<rclcpp::ParameterEventHandler> _remote_param_subscriber;
141  std::shared_ptr<rclcpp::ParameterCallbackHandle> _remote_resolution_handler;
142 };
143 
144 } // namespace nav2_smac_planner
145 
146 #endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_
Abstract interface for global planners to adhere to with pluginlib.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
A costmap grid collision checker.
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.
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
Configuring plugin.
void activate() override
Activate lifecycle node.
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Search properties and penalties.
Definition: types.hpp:36