15 #include <ompl/base/ScopedState.h>
16 #include <ompl/base/spaces/DubinsStateSpace.h>
17 #include <ompl/base/spaces/ReedsSheppStateSpace.h>
23 #include "nav2_smac_planner/analytic_expansion.hpp"
25 namespace nav2_smac_planner
28 template<
typename NodeT>
30 const MotionModel & motion_model,
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)
42 template<
typename NodeT>
46 _collision_checker = collision_checker;
49 template<
typename NodeT>
51 const NodePtr & current_node,
const NodePtr & goal_node,
52 const NodeGetter & getter,
int & analytic_iterations,
53 int & closest_distance)
56 if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP ||
57 _motion_model == MotionModel::STATE_LATTICE)
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(
65 static_cast<int>(NodeT::getHeuristicCost(node_coords, goal_node->pose, costmap)));
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)));
76 std::min(analytic_iterations, desired_iterations);
80 if (analytic_iterations <= 0) {
82 analytic_iterations = desired_iterations;
83 AnalyticExpansionNodes analytic_nodes = getAnalyticPath(current_node, goal_node, getter);
84 if (!analytic_nodes.empty()) {
86 NodePtr node = current_node;
87 NodePtr test_node = current_node;
88 AnalyticExpansionNodes refined_analytic_nodes;
89 for (
int i = 0; i < 8; i++) {
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)
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()) {
101 analytic_nodes = refined_analytic_nodes;
108 return setAnalyticPath(node, goal_node, analytic_nodes);
112 analytic_iterations--;
116 return NodePtr(
nullptr);
119 template<
typename NodeT>
121 const NodePtr & node,
122 const NodePtr & goal,
123 const NodeGetter & node_getter)
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);
134 float d = node->motion_table.state_space->distance(from(), to());
140 if (d > _search_info.analytic_expansion_max_length) {
141 return AnalyticExpansionNodes();
145 static const float sqrt_2 = std::sqrt(2.);
146 unsigned int num_intervals = std::floor(d / sqrt_2);
148 AnalyticExpansionNodes possible_nodes;
151 possible_nodes.reserve(num_intervals);
152 std::vector<double> reals;
157 unsigned int index = 0;
158 NodePtr next(
nullptr);
160 Coordinates proposed_coordinates;
161 bool failure =
false;
164 for (
float i = 1; i <= num_intervals; i++) {
165 node->motion_table.state_space->interpolate(from(), to(), i / num_intervals, s());
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);
173 index = NodeT::getIndex(
174 static_cast<unsigned int>(reals[0]),
175 static_cast<unsigned int>(reals[1]),
176 static_cast<unsigned int>(angle));
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) {
184 possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates);
188 next->setPose(initial_node_coords);
200 for (
const auto & node_pose : possible_nodes) {
201 const auto & n = node_pose.node;
202 n->setPose(node_pose.initial_coords);
206 return AnalyticExpansionNodes();
209 return possible_nodes;
212 template<
typename NodeT>
214 const NodePtr & node,
215 const NodePtr & goal_node,
216 const AnalyticExpansionNodes & expanded_nodes)
218 _detached_nodes.clear();
221 for (
const auto & node_pose : expanded_nodes) {
222 auto n = node_pose.node;
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();
230 n->pose = node_pose.proposed_coords;
235 if (goal_node != prev) {
236 goal_node->parent = prev;
237 cleanNode(goal_node);
238 goal_node->visited();
246 node->setMotionPrimitive(
nullptr);
249 template<
typename NodeT>
257 const NodePtr & node,
258 const NodePtr & goal,
259 const NodeGetter & node_getter)
266 const NodePtr & node,
267 const NodePtr & goal_node,
270 return NodePtr(
nullptr);
275 const NodePtr & current_node,
const NodePtr & goal_node,
276 const NodeGetter & getter,
int & analytic_iterations,
277 int & closest_distance)
279 return NodePtr(
nullptr);
282 template class AnalyticExpansion<Node2D>;
283 template class AnalyticExpansion<NodeHybrid>;
284 template class AnalyticExpansion<NodeLattice>;
NodePtr tryAnalyticExpansion(const NodePtr ¤t_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.