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 const Coordinates node_coords =
62 current_node->getIndex(), _collision_checker->getCostmap()->getSizeInCellsX(), _dim_3_size);
63 closest_distance = std::min(
65 static_cast<int>(NodeT::getHeuristicCost(node_coords, goal_node->pose)));
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 =
84 getAnalyticPath(current_node, goal_node, getter, current_node->motion_table.state_space);
85 if (!analytic_nodes.empty()) {
87 NodePtr node = current_node;
88 NodePtr test_node = current_node;
89 AnalyticExpansionNodes refined_analytic_nodes;
90 for (
int i = 0; i < 8; i++) {
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)
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()) {
103 analytic_nodes = refined_analytic_nodes;
114 auto scoringFn = [&](
const AnalyticExpansionNodes & expansion) {
115 if (expansion.size() < 2) {
116 return std::numeric_limits<float>::max();
120 float normalized_cost = 0.0;
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;
129 score += distance * (1.0 + weight * normalized_cost);
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;
138 while (min_turn_rad < max_min_turn_rad) {
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);
144 state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(min_turn_rad);
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;
154 return setAnalyticPath(node, goal_node, analytic_nodes);
158 analytic_iterations--;
162 return NodePtr(
nullptr);
165 template<
typename NodeT>
167 const NodePtr & node,
168 const NodePtr & goal,
169 const NodeGetter & node_getter,
170 const ompl::base::StateSpacePtr & state_space)
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);
180 float d = state_space->distance(from(), to());
183 static const float sqrt_2 = sqrtf(2.0f);
189 if (d > _search_info.analytic_expansion_max_length || d < sqrt_2) {
190 return AnalyticExpansionNodes();
193 unsigned int num_intervals =
static_cast<unsigned int>(std::floor(d / sqrt_2));
195 AnalyticExpansionNodes possible_nodes;
198 possible_nodes.reserve(num_intervals);
199 std::vector<double> reals;
205 NodePtr next(
nullptr);
207 Coordinates proposed_coordinates;
208 bool failure =
false;
209 std::vector<float> node_costs;
210 node_costs.reserve(num_intervals);
213 for (
float i = 1; i <= num_intervals; i++) {
214 state_space->interpolate(from(), to(), i / num_intervals, s());
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);
222 index = NodeT::getIndex(
223 static_cast<unsigned int>(reals[0]),
224 static_cast<unsigned int>(reals[1]),
225 static_cast<unsigned int>(angle));
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) {
233 possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates);
234 node_costs.emplace_back(next->getCost());
238 next->setPose(initial_node_coords);
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) {
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) {
273 if (d < 2.0f * M_PI * goal->motion_table.min_turning_radius &&
274 _search_info.analytic_expansion_max_cost_override)
283 for (
const auto & node_pose : possible_nodes) {
284 const auto & n = node_pose.node;
285 n->setPose(node_pose.initial_coords);
289 return AnalyticExpansionNodes();
292 return possible_nodes;
295 template<
typename NodeT>
297 const NodePtr & node,
298 const NodePtr & goal_node,
299 const AnalyticExpansionNodes & expanded_nodes)
301 _detached_nodes.clear();
304 for (
const auto & node_pose : expanded_nodes) {
305 auto n = node_pose.node;
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();
313 n->pose = node_pose.proposed_coords;
318 if (goal_node != prev) {
319 goal_node->parent = prev;
320 cleanNode(goal_node);
321 goal_node->visited();
329 node->setMotionPrimitive(
nullptr);
332 template<
typename NodeT>
340 const NodePtr & node,
341 const NodePtr & goal,
342 const NodeGetter & node_getter,
343 const ompl::base::StateSpacePtr & state_space)
350 const NodePtr & node,
351 const NodePtr & goal_node,
354 return NodePtr(
nullptr);
359 const NodePtr & current_node,
const NodePtr & goal_node,
360 const NodeGetter & getter,
int & analytic_iterations,
361 int & closest_distance)
363 return NodePtr(
nullptr);
366 template class AnalyticExpansion<Node2D>;
367 template class AnalyticExpansion<NodeHybrid>;
368 template class AnalyticExpansion<NodeLattice>;
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 ¤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.
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.