Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
analytic_expansion.cpp
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 #include <ompl/base/ScopedState.h>
16 #include <ompl/base/spaces/DubinsStateSpace.h>
17 #include <ompl/base/spaces/ReedsSheppStateSpace.h>
18 
19 #include <algorithm>
20 #include <vector>
21 #include <memory>
22 
23 #include "nav2_smac_planner/analytic_expansion.hpp"
24 
25 namespace nav2_smac_planner
26 {
27 
28 template<typename NodeT>
30  const MotionModel & motion_model,
31  const SearchInfo & search_info,
32  const bool & traverse_unknown,
33  const unsigned int & dim_3_size)
34 : _motion_model(motion_model),
35  _search_info(search_info),
36  _traverse_unknown(traverse_unknown),
37  _dim_3_size(dim_3_size),
38  _collision_checker(nullptr)
39 {
40 }
41 
42 template<typename NodeT>
44  GridCollisionChecker * collision_checker)
45 {
46  _collision_checker = collision_checker;
47 }
48 
49 template<typename NodeT>
50 typename AnalyticExpansion<NodeT>::NodePtr AnalyticExpansion<NodeT>::tryAnalyticExpansion(
51  const NodePtr & current_node, const NodePtr & goal_node,
52  const NodeGetter & getter, int & analytic_iterations,
53  int & closest_distance)
54 {
55  // This must be a valid motion model for analytic expansion to be attempted
56  if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP ||
57  _motion_model == MotionModel::STATE_LATTICE)
58  {
59  // See if we are closer and should be expanding more often
60  auto costmap = _collision_checker->getCostmap();
61  const Coordinates node_coords =
62  NodeT::getCoords(current_node->getIndex(), costmap->getSizeInCellsX(), _dim_3_size);
63  closest_distance = std::min(
64  closest_distance,
65  static_cast<int>(NodeT::getHeuristicCost(node_coords, goal_node->pose, costmap)));
66 
67  // We want to expand at a rate of d/expansion_ratio,
68  // but check to see if we are so close that we would be expanding every iteration
69  // If so, limit it to the expansion ratio (rounded up)
70  int desired_iterations = std::max(
71  static_cast<int>(closest_distance / _search_info.analytic_expansion_ratio),
72  static_cast<int>(std::ceil(_search_info.analytic_expansion_ratio)));
73 
74  // If we are closer now, we should update the target number of iterations to go
75  analytic_iterations =
76  std::min(analytic_iterations, desired_iterations);
77 
78  // Always run the expansion on the first run in case there is a
79  // trivial path to be found
80  if (analytic_iterations <= 0) {
81  // Reset the counter and try the analytic path expansion
82  analytic_iterations = desired_iterations;
83  AnalyticExpansionNodes analytic_nodes = getAnalyticPath(current_node, goal_node, getter);
84  if (!analytic_nodes.empty()) {
85  // If we have a valid path, attempt to refine it
86  NodePtr node = current_node;
87  NodePtr test_node = current_node;
88  AnalyticExpansionNodes refined_analytic_nodes;
89  for (int i = 0; i < 8; i++) {
90  // Attempt to create better paths in 5 node increments, need to make sure
91  // they exist for each in order to do so (maximum of 40 points back).
92  if (test_node->parent && test_node->parent->parent && test_node->parent->parent->parent &&
93  test_node->parent->parent->parent->parent &&
94  test_node->parent->parent->parent->parent->parent)
95  {
96  test_node = test_node->parent->parent->parent->parent->parent;
97  refined_analytic_nodes = getAnalyticPath(test_node, goal_node, getter);
98  if (refined_analytic_nodes.empty()) {
99  break;
100  }
101  analytic_nodes = refined_analytic_nodes;
102  node = test_node;
103  } else {
104  break;
105  }
106  }
107 
108  return setAnalyticPath(node, goal_node, analytic_nodes);
109  }
110  }
111 
112  analytic_iterations--;
113  }
114 
115  // No valid motion model - return nullptr
116  return NodePtr(nullptr);
117 }
118 
119 template<typename NodeT>
120 typename AnalyticExpansion<NodeT>::AnalyticExpansionNodes AnalyticExpansion<NodeT>::getAnalyticPath(
121  const NodePtr & node,
122  const NodePtr & goal,
123  const NodeGetter & node_getter)
124 {
125  static ompl::base::ScopedState<> from(node->motion_table.state_space), to(
126  node->motion_table.state_space), s(node->motion_table.state_space);
127  from[0] = node->pose.x;
128  from[1] = node->pose.y;
129  from[2] = node->motion_table.getAngleFromBin(node->pose.theta);
130  to[0] = goal->pose.x;
131  to[1] = goal->pose.y;
132  to[2] = node->motion_table.getAngleFromBin(goal->pose.theta);
133 
134  float d = node->motion_table.state_space->distance(from(), to());
135 
136  // If the length is too far, exit. This prevents unsafe shortcutting of paths
137  // into higher cost areas far out from the goal itself, let search to the work of getting
138  // close before the analytic expansion brings it home. This should never be smaller than
139  // 4-5x the minimum turning radius being used, or planning times will begin to spike.
140  if (d > _search_info.analytic_expansion_max_length) {
141  return AnalyticExpansionNodes();
142  }
143 
144  // A move of sqrt(2) is guaranteed to be in a new cell
145  static const float sqrt_2 = std::sqrt(2.);
146  unsigned int num_intervals = std::floor(d / sqrt_2);
147 
148  AnalyticExpansionNodes possible_nodes;
149  // When "from" and "to" are zero or one cell away,
150  // num_intervals == 0
151  possible_nodes.reserve(num_intervals); // We won't store this node or the goal
152  std::vector<double> reals;
153  double theta;
154 
155  // Pre-allocate
156  NodePtr prev(node);
157  unsigned int index = 0;
158  NodePtr next(nullptr);
159  float angle = 0.0;
160  Coordinates proposed_coordinates;
161  bool failure = false;
162 
163  // Check intermediary poses (non-goal, non-start)
164  for (float i = 1; i <= num_intervals; i++) {
165  node->motion_table.state_space->interpolate(from(), to(), i / num_intervals, s());
166  reals = s.reals();
167  // Make sure in range [0, 2PI)
168  theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
169  theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
170  angle = node->motion_table.getClosestAngularBin(theta);
171 
172  // Turn the pose into a node, and check if it is valid
173  index = NodeT::getIndex(
174  static_cast<unsigned int>(reals[0]),
175  static_cast<unsigned int>(reals[1]),
176  static_cast<unsigned int>(angle));
177  // Get the node from the graph
178  if (node_getter(index, next)) {
179  Coordinates initial_node_coords = next->pose;
180  proposed_coordinates = {static_cast<float>(reals[0]), static_cast<float>(reals[1]), angle};
181  next->setPose(proposed_coordinates);
182  if (next->isNodeValid(_traverse_unknown, _collision_checker) && next != prev) {
183  // Save the node, and its previous coordinates in case we need to abort
184  possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates);
185  prev = next;
186  } else {
187  // Abort
188  next->setPose(initial_node_coords);
189  failure = true;
190  break;
191  }
192  } else {
193  // Abort
194  failure = true;
195  break;
196  }
197  }
198 
199  // Reset to initial poses to not impact future searches
200  for (const auto & node_pose : possible_nodes) {
201  const auto & n = node_pose.node;
202  n->setPose(node_pose.initial_coords);
203  }
204 
205  if (failure) {
206  return AnalyticExpansionNodes();
207  }
208 
209  return possible_nodes;
210 }
211 
212 template<typename NodeT>
213 typename AnalyticExpansion<NodeT>::NodePtr AnalyticExpansion<NodeT>::setAnalyticPath(
214  const NodePtr & node,
215  const NodePtr & goal_node,
216  const AnalyticExpansionNodes & expanded_nodes)
217 {
218  _detached_nodes.clear();
219  // Legitimate final path - set the parent relationships, states, and poses
220  NodePtr prev = node;
221  for (const auto & node_pose : expanded_nodes) {
222  auto n = node_pose.node;
223  cleanNode(n);
224  if (n->getIndex() != goal_node->getIndex()) {
225  if (n->wasVisited()) {
226  _detached_nodes.push_back(std::make_unique<NodeT>(-1));
227  n = _detached_nodes.back().get();
228  }
229  n->parent = prev;
230  n->pose = node_pose.proposed_coords;
231  n->visited();
232  prev = n;
233  }
234  }
235  if (goal_node != prev) {
236  goal_node->parent = prev;
237  cleanNode(goal_node);
238  goal_node->visited();
239  }
240  return goal_node;
241 }
242 
243 template<>
244 void AnalyticExpansion<NodeLattice>::cleanNode(const NodePtr & node)
245 {
246  node->setMotionPrimitive(nullptr);
247 }
248 
249 template<typename NodeT>
250 void AnalyticExpansion<NodeT>::cleanNode(const NodePtr & /*expanded_nodes*/)
251 {
252 }
253 
254 template<>
255 typename AnalyticExpansion<Node2D>::AnalyticExpansionNodes AnalyticExpansion<Node2D>::
257  const NodePtr & node,
258  const NodePtr & goal,
259  const NodeGetter & node_getter)
260 {
261  return AnalyticExpansionNodes();
262 }
263 
264 template<>
265 typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::setAnalyticPath(
266  const NodePtr & node,
267  const NodePtr & goal_node,
268  const AnalyticExpansionNodes & expanded_nodes)
269 {
270  return NodePtr(nullptr);
271 }
272 
273 template<>
274 typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::tryAnalyticExpansion(
275  const NodePtr & current_node, const NodePtr & goal_node,
276  const NodeGetter & getter, int & analytic_iterations,
277  int & closest_distance)
278 {
279  return NodePtr(nullptr);
280 }
281 
282 template class AnalyticExpansion<Node2D>;
283 template class AnalyticExpansion<NodeHybrid>;
284 template class AnalyticExpansion<NodeLattice>;
285 
286 } // namespace nav2_smac_planner
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.
AnalyticExpansionNodes getAnalyticPath(const NodePtr &node, const NodePtr &goal, const NodeGetter &getter)
Perform an analytic path expansion to the goal.
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.
Analytic expansion nodes and associated metadata.
Search properties and penalties.
Definition: types.hpp:36