Nav2 Navigation Stack - jazzy  jazzy
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  const Coordinates node_coords =
61  NodeT::getCoords(
62  current_node->getIndex(), _collision_checker->getCostmap()->getSizeInCellsX(), _dim_3_size);
63  closest_distance = std::min(
64  closest_distance,
65  static_cast<int>(NodeT::getHeuristicCost(node_coords, goal_node->pose)));
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 =
84  getAnalyticPath(current_node, goal_node, getter, current_node->motion_table.state_space);
85  if (!analytic_nodes.empty()) {
86  // If we have a valid path, attempt to refine it
87  NodePtr node = current_node;
88  NodePtr test_node = current_node;
89  AnalyticExpansionNodes refined_analytic_nodes;
90  for (int i = 0; i < 8; i++) {
91  // Attempt to create better paths in 5 node increments, need to make sure
92  // they exist for each in order to do so (maximum of 40 points back).
93  if (test_node->parent && test_node->parent->parent && test_node->parent->parent->parent &&
94  test_node->parent->parent->parent->parent &&
95  test_node->parent->parent->parent->parent->parent)
96  {
97  test_node = test_node->parent->parent->parent->parent->parent;
98  refined_analytic_nodes =
99  getAnalyticPath(test_node, goal_node, getter, test_node->motion_table.state_space);
100  if (refined_analytic_nodes.empty()) {
101  break;
102  }
103  analytic_nodes = refined_analytic_nodes;
104  node = test_node;
105  } else {
106  break;
107  }
108  }
109 
110  // The analytic expansion can short-cut near obstacles when closer to a goal
111  // So, we can attempt to refine it more by increasing the possible radius
112  // higher than the minimum turning radius and use the best solution based on
113  // a scoring function similar to that used in traveral cost estimation.
114  auto scoringFn = [&](const AnalyticExpansionNodes & expansion) {
115  if (expansion.size() < 2) {
116  return std::numeric_limits<float>::max();
117  }
118 
119  float score = 0.0;
120  float normalized_cost = 0.0;
121  // Analytic expansions are consistently spaced
122  const float distance = hypotf(
123  expansion[1].proposed_coords.x - expansion[0].proposed_coords.x,
124  expansion[1].proposed_coords.y - expansion[0].proposed_coords.y);
125  const float & weight = expansion[0].node->motion_table.cost_penalty;
126  for (auto iter = expansion.begin(); iter != expansion.end(); ++iter) {
127  normalized_cost = iter->node->getCost() / 252.0f;
128  // Search's Traversal Cost Function
129  score += distance * (1.0 + weight * normalized_cost);
130  }
131  return score;
132  };
133 
134  float best_score = scoringFn(analytic_nodes);
135  float score = std::numeric_limits<float>::max();
136  float min_turn_rad = node->motion_table.min_turning_radius;
137  const float max_min_turn_rad = 4.0 * min_turn_rad; // Up to 4x the turning radius
138  while (min_turn_rad < max_min_turn_rad) {
139  min_turn_rad += 0.5; // In Grid Coords, 1/2 cell steps
140  ompl::base::StateSpacePtr state_space;
141  if (node->motion_table.motion_model == MotionModel::DUBIN) {
142  state_space = std::make_shared<ompl::base::DubinsStateSpace>(min_turn_rad);
143  } else {
144  state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(min_turn_rad);
145  }
146  refined_analytic_nodes = getAnalyticPath(node, goal_node, getter, state_space);
147  score = scoringFn(refined_analytic_nodes);
148  if (score <= best_score) {
149  analytic_nodes = refined_analytic_nodes;
150  best_score = score;
151  }
152  }
153 
154  return setAnalyticPath(node, goal_node, analytic_nodes);
155  }
156  }
157 
158  analytic_iterations--;
159  }
160 
161  // No valid motion model - return nullptr
162  return NodePtr(nullptr);
163 }
164 
165 template<typename NodeT>
166 typename AnalyticExpansion<NodeT>::AnalyticExpansionNodes AnalyticExpansion<NodeT>::getAnalyticPath(
167  const NodePtr & node,
168  const NodePtr & goal,
169  const NodeGetter & node_getter,
170  const ompl::base::StateSpacePtr & state_space)
171 {
172  static ompl::base::ScopedState<> from(state_space), to(state_space), s(state_space);
173  from[0] = node->pose.x;
174  from[1] = node->pose.y;
175  from[2] = node->motion_table.getAngleFromBin(node->pose.theta);
176  to[0] = goal->pose.x;
177  to[1] = goal->pose.y;
178  to[2] = node->motion_table.getAngleFromBin(goal->pose.theta);
179 
180  float d = state_space->distance(from(), to());
181 
182  // A move of sqrt(2) is guaranteed to be in a new cell
183  static const float sqrt_2 = sqrtf(2.0f);
184 
185  // If the length is too far, exit. This prevents unsafe shortcutting of paths
186  // into higher cost areas far out from the goal itself, let search to the work of getting
187  // close before the analytic expansion brings it home. This should never be smaller than
188  // 4-5x the minimum turning radius being used, or planning times will begin to spike.
189  if (d > _search_info.analytic_expansion_max_length || d < sqrt_2) {
190  return AnalyticExpansionNodes();
191  }
192 
193  unsigned int num_intervals = static_cast<unsigned int>(std::floor(d / sqrt_2));
194 
195  AnalyticExpansionNodes possible_nodes;
196  // When "from" and "to" are zero or one cell away,
197  // num_intervals == 0
198  possible_nodes.reserve(num_intervals); // We won't store this node or the goal
199  std::vector<double> reals;
200  double theta;
201 
202  // Pre-allocate
203  NodePtr prev(node);
204  uint64_t index = 0;
205  NodePtr next(nullptr);
206  float angle = 0.0;
207  Coordinates proposed_coordinates;
208  bool failure = false;
209  std::vector<float> node_costs;
210  node_costs.reserve(num_intervals);
211 
212  // Check intermediary poses (non-goal, non-start)
213  for (float i = 1; i <= num_intervals; i++) {
214  state_space->interpolate(from(), to(), i / num_intervals, s());
215  reals = s.reals();
216  // Make sure in range [0, 2PI)
217  theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
218  theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
219  angle = node->motion_table.getAngle(theta);
220 
221  // Turn the pose into a node, and check if it is valid
222  index = NodeT::getIndex(
223  static_cast<unsigned int>(reals[0]),
224  static_cast<unsigned int>(reals[1]),
225  static_cast<unsigned int>(angle));
226  // Get the node from the graph
227  if (node_getter(index, next)) {
228  Coordinates initial_node_coords = next->pose;
229  proposed_coordinates = {static_cast<float>(reals[0]), static_cast<float>(reals[1]), angle};
230  next->setPose(proposed_coordinates);
231  if (next->isNodeValid(_traverse_unknown, _collision_checker) && next != prev) {
232  // Save the node, and its previous coordinates in case we need to abort
233  possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates);
234  node_costs.emplace_back(next->getCost());
235  prev = next;
236  } else {
237  // Abort
238  next->setPose(initial_node_coords);
239  failure = true;
240  break;
241  }
242  } else {
243  // Abort
244  failure = true;
245  break;
246  }
247  }
248 
249  if (!failure) {
250  // We found 'a' valid expansion. Now to tell if its a quality option...
251  const float max_cost = _search_info.analytic_expansion_max_cost;
252  auto max_cost_it = std::max_element(node_costs.begin(), node_costs.end());
253  if (max_cost_it != node_costs.end() && *max_cost_it > max_cost) {
254  // If any element is above the comfortable cost limit, check edge cases:
255  // (1) Check if goal is in greater than max_cost space requiring
256  // entering it, but only entering it on final approach, not in-and-out
257  // (2) Checks if goal is in normal space, but enters costed space unnecessarily
258  // mid-way through, skirting obstacle or in non-globally confined space
259  bool cost_exit_high_cost_region = false;
260  for (auto iter = node_costs.rbegin(); iter != node_costs.rend(); ++iter) {
261  const float & curr_cost = *iter;
262  if (curr_cost <= max_cost) {
263  cost_exit_high_cost_region = true;
264  } else if (curr_cost > max_cost && cost_exit_high_cost_region) {
265  failure = true;
266  break;
267  }
268  }
269 
270  // (3) Handle exception: there may be no other option close to goal
271  // if max cost is set too low (optional)
272  if (failure) {
273  if (d < 2.0f * M_PI * goal->motion_table.min_turning_radius &&
274  _search_info.analytic_expansion_max_cost_override)
275  {
276  failure = false;
277  }
278  }
279  }
280  }
281 
282  // Reset to initial poses to not impact future searches
283  for (const auto & node_pose : possible_nodes) {
284  const auto & n = node_pose.node;
285  n->setPose(node_pose.initial_coords);
286  }
287 
288  if (failure) {
289  return AnalyticExpansionNodes();
290  }
291 
292  return possible_nodes;
293 }
294 
295 template<typename NodeT>
296 typename AnalyticExpansion<NodeT>::NodePtr AnalyticExpansion<NodeT>::setAnalyticPath(
297  const NodePtr & node,
298  const NodePtr & goal_node,
299  const AnalyticExpansionNodes & expanded_nodes)
300 {
301  _detached_nodes.clear();
302  // Legitimate final path - set the parent relationships, states, and poses
303  NodePtr prev = node;
304  for (const auto & node_pose : expanded_nodes) {
305  auto n = node_pose.node;
306  cleanNode(n);
307  if (n->getIndex() != goal_node->getIndex()) {
308  if (n->wasVisited()) {
309  _detached_nodes.push_back(std::make_unique<NodeT>(-1));
310  n = _detached_nodes.back().get();
311  }
312  n->parent = prev;
313  n->pose = node_pose.proposed_coords;
314  n->visited();
315  prev = n;
316  }
317  }
318  if (goal_node != prev) {
319  goal_node->parent = prev;
320  cleanNode(goal_node);
321  goal_node->visited();
322  }
323  return goal_node;
324 }
325 
326 template<>
327 void AnalyticExpansion<NodeLattice>::cleanNode(const NodePtr & node)
328 {
329  node->setMotionPrimitive(nullptr);
330 }
331 
332 template<typename NodeT>
333 void AnalyticExpansion<NodeT>::cleanNode(const NodePtr & /*expanded_nodes*/)
334 {
335 }
336 
337 template<>
338 typename AnalyticExpansion<Node2D>::AnalyticExpansionNodes AnalyticExpansion<Node2D>::
340  const NodePtr & node,
341  const NodePtr & goal,
342  const NodeGetter & node_getter,
343  const ompl::base::StateSpacePtr & state_space)
344 {
345  return AnalyticExpansionNodes();
346 }
347 
348 template<>
349 typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::setAnalyticPath(
350  const NodePtr & node,
351  const NodePtr & goal_node,
352  const AnalyticExpansionNodes & expanded_nodes)
353 {
354  return NodePtr(nullptr);
355 }
356 
357 template<>
358 typename AnalyticExpansion<Node2D>::NodePtr AnalyticExpansion<Node2D>::tryAnalyticExpansion(
359  const NodePtr & current_node, const NodePtr & goal_node,
360  const NodeGetter & getter, int & analytic_iterations,
361  int & closest_distance)
362 {
363  return NodePtr(nullptr);
364 }
365 
366 template class AnalyticExpansion<Node2D>;
367 template class AnalyticExpansion<NodeHybrid>;
368 template class AnalyticExpansion<NodeLattice>;
369 
370 } // namespace nav2_smac_planner
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.
Analytic expansion nodes and associated metadata.
Search properties and penalties.
Definition: types.hpp:36