Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
analytic_expansion.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__ANALYTIC_EXPANSION_HPP_
16 #define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <list>
21 #include <memory>
22 
23 #include "nav2_smac_planner/node_2d.hpp"
24 #include "nav2_smac_planner/node_hybrid.hpp"
25 #include "nav2_smac_planner/node_lattice.hpp"
26 #include "nav2_smac_planner/types.hpp"
27 #include "nav2_smac_planner/constants.hpp"
28 
29 namespace nav2_smac_planner
30 {
31 
32 template<typename NodeT>
34 {
35 public:
36  typedef NodeT * NodePtr;
37  typedef typename NodeT::Coordinates Coordinates;
38  typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
39 
45  {
47  NodePtr & node_in,
48  Coordinates & initial_coords_in,
49  Coordinates & proposed_coords_in)
50  : node(node_in),
51  initial_coords(initial_coords_in),
52  proposed_coords(proposed_coords_in)
53  {
54  }
55 
56  NodePtr node;
57  Coordinates initial_coords;
58  Coordinates proposed_coords;
59  };
60 
61  typedef std::vector<AnalyticExpansionNode> AnalyticExpansionNodes;
62 
67  const MotionModel & motion_model,
68  const SearchInfo & search_info,
69  const bool & traverse_unknown,
70  const unsigned int & dim_3_size);
71 
76  void setCollisionChecker(GridCollisionChecker * collision_checker);
77 
88  NodePtr tryAnalyticExpansion(
89  const NodePtr & current_node,
90  const NodePtr & goal_node,
91  const NodeGetter & getter, int & iterations, int & best_cost);
92 
101  AnalyticExpansionNodes getAnalyticPath(
102  const NodePtr & node, const NodePtr & goal,
103  const NodeGetter & getter, const ompl::base::StateSpacePtr & state_space);
104 
112  NodePtr setAnalyticPath(
113  const NodePtr & node, const NodePtr & goal,
114  const AnalyticExpansionNodes & expanded_nodes);
115 
121  void cleanNode(const NodePtr & nodes);
122 
123 protected:
124  MotionModel _motion_model;
125  SearchInfo _search_info;
126  bool _traverse_unknown;
127  unsigned int _dim_3_size;
128  GridCollisionChecker * _collision_checker;
129  std::list<std::unique_ptr<NodeT>> _detached_nodes;
130 };
131 
132 } // namespace nav2_smac_planner
133 
134 #endif // NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
AnalyticExpansionNodes getAnalyticPath(const NodePtr &node, const NodePtr &goal, const NodeGetter &getter, const ompl::base::StateSpacePtr &state_space)
Perform an analytic path expansion to the goal.
NodePtr tryAnalyticExpansion(const NodePtr &current_node, const NodePtr &goal_node, const NodeGetter &getter, int &iterations, int &best_cost)
Attempt an analytic path completion.
void cleanNode(const NodePtr &nodes)
Takes an expanded nodes to clean up, if necessary, of any state information that may be poluting it f...
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker and costmap to use in expansion validation.
AnalyticExpansion(const MotionModel &motion_model, const SearchInfo &search_info, const bool &traverse_unknown, const unsigned int &dim_3_size)
Constructor for analytic expansion object.
NodePtr setAnalyticPath(const NodePtr &node, const NodePtr &goal, const AnalyticExpansionNodes &expanded_nodes)
Takes final analytic expansion and appends to current expanded node.
A costmap grid collision checker.
Search properties and penalties.
Definition: types.hpp:36