Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smac_planner_lattice.hpp
1 // Copyright (c) 2021, 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_LATTICE_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_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 "nav_msgs/msg/occupancy_grid.hpp"
26 #include "nav2_core/global_planner.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
29 #include "nav2_costmap_2d/costmap_2d.hpp"
30 #include "geometry_msgs/msg/pose_array.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "nav2_ros_common/lifecycle_node.hpp"
33 #include "nav2_ros_common/node_utils.hpp"
34 #include "tf2/utils.hpp"
35 
36 namespace nav2_smac_planner
37 {
38 
40 {
41 public:
46 
51 
59  void configure(
60  const nav2::LifecycleNode::WeakPtr & parent,
61  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
62  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
63 
67  void cleanup() override;
68 
72  void activate() override;
73 
77  void deactivate() override;
78 
86  nav_msgs::msg::Path createPlan(
87  const geometry_msgs::msg::PoseStamped & start,
88  const geometry_msgs::msg::PoseStamped & goal,
89  std::function<bool()> cancel_checker) override;
90 
91 protected:
96  rcl_interfaces::msg::SetParametersResult
97  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
98 
99  std::unique_ptr<AStarAlgorithm<NodeLattice>> _a_star;
100  GridCollisionChecker _collision_checker;
101  std::unique_ptr<Smoother> _smoother;
102  rclcpp::Clock::SharedPtr _clock;
103  rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerLattice")};
104  nav2_costmap_2d::Costmap2D * _costmap;
105  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> _costmap_ros;
106  MotionModel _motion_model;
107  LatticeMetadata _metadata;
108  std::string _global_frame, _name;
109  SearchInfo _search_info;
110  bool _allow_unknown;
111  int _max_iterations;
112  int _max_on_approach_iterations;
113  int _terminal_checking_interval;
114  float _tolerance;
115  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
116  double _max_planning_time;
117  double _lookup_table_size;
118  bool _debug_visualizations;
119  nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
120  _planned_footprints_publisher;
121  nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
122  _smoothed_footprints_publisher;
123  nav2::Publisher<geometry_msgs::msg::PoseArray>::SharedPtr
124  _expansions_publisher;
125  GoalHeadingMode _goal_heading_mode;
126  int _coarse_search_resolution;
127  std::mutex _mutex;
128  nav2::LifecycleNode::WeakPtr _node;
129 
130  // Dynamic parameters handler
131  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler;
132 };
133 
134 } // namespace nav2_smac_planner
135 
136 #endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_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 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.
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 activate() override
Activate lifecycle node.
A struct of all lattice metadata.
Definition: types.hpp:165
Search properties and penalties.
Definition: types.hpp:36