Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smac_planner_2d.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_2D_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_2D_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 #include <mutex>
22 
23 #include "nav2_smac_planner/a_star.hpp"
24 #include "nav2_smac_planner/smoother.hpp"
25 #include "nav2_smac_planner/utils.hpp"
26 #include "nav2_smac_planner/costmap_downsampler.hpp"
27 #include "nav_msgs/msg/occupancy_grid.hpp"
28 #include "nav2_core/global_planner.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
31 #include "nav2_costmap_2d/costmap_2d.hpp"
32 #include "geometry_msgs/msg/pose_stamped.hpp"
33 #include "nav2_ros_common/lifecycle_node.hpp"
34 #include "nav2_ros_common/node_utils.hpp"
35 #include "tf2/utils.hpp"
36 #include "rcl_interfaces/msg/set_parameters_result.hpp"
37 
38 namespace nav2_smac_planner
39 {
40 
42 {
43 public:
47  SmacPlanner2D();
48 
53 
61  void configure(
62  const nav2::LifecycleNode::WeakPtr & parent,
63  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
64  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
65 
69  void cleanup() override;
70 
74  void activate() override;
75 
79  void deactivate() override;
80 
88  nav_msgs::msg::Path createPlan(
89  const geometry_msgs::msg::PoseStamped & start,
90  const geometry_msgs::msg::PoseStamped & goal,
91  std::function<bool()> cancel_checker) override;
92 
93 protected:
98  rcl_interfaces::msg::SetParametersResult
99  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
100 
101  std::unique_ptr<AStarAlgorithm<Node2D>> _a_star;
102  GridCollisionChecker _collision_checker;
103  std::unique_ptr<Smoother> _smoother;
104  nav2_costmap_2d::Costmap2D * _costmap;
105  std::unique_ptr<CostmapDownsampler> _costmap_downsampler;
106  rclcpp::Clock::SharedPtr _clock;
107  rclcpp::Logger _logger{rclcpp::get_logger("SmacPlanner2D")};
108  std::string _global_frame, _name;
109  float _tolerance;
110  int _downsampling_factor;
111  bool _downsample_costmap;
112  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
113  double _max_planning_time;
114  bool _allow_unknown;
115  int _max_iterations;
116  int _max_on_approach_iterations;
117  int _terminal_checking_interval;
118  bool _use_final_approach_orientation;
119  SearchInfo _search_info;
120  std::string _motion_model_for_search;
121  MotionModel _motion_model;
122  std::mutex _mutex;
123  nav2::LifecycleNode::WeakPtr _node;
124 
125  // Dynamic parameters handler
126  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler;
127 };
128 
129 } // namespace nav2_smac_planner
130 
131 #endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_2D_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.
void activate() override
Activate lifecycle node.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void cleanup() override
Cleanup lifecycle node.
void configure(const nav2::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 deactivate() override
Deactivate lifecycle node.
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.
Search properties and penalties.
Definition: types.hpp:36