AStarPlanner.cpp
Go to the documentation of this file.
1#include "AStarPlanner.h"
2
3#include <math.h>
4
5#include <algorithm>
6#include <cmath>
7#include <cstddef>
8#include <experimental/memory>
9#include <map>
10#include <memory>
11#include <optional>
12#include <queue>
13#include <vector>
14
15#include <Eigen/Geometry>
16
17#include <qnamespace.h>
18
19#include <range/v3/algorithm/reverse.hpp>
20#include <range/v3/range/conversion.hpp>
21#include <range/v3/view/map.hpp>
22#include <range/v3/view/transform.hpp>
23
28
34
35#include <omp.h>
36
38{
39
40 Grid::Grid(int rows, int cols, int orientations, const Costmap3D& costmap)
41 {
42 initialize(rows, cols, orientations, costmap);
43 }
44
45 void
47 {
48 for (int r = 0; r < rows; r++)
49 {
50 for (int c = 0; c < cols; c++)
51 {
52 for (int rot_idx = 0; rot_idx < orientations; rot_idx++)
53 {
54 Node& node = getNode(r, c, rot_idx);
55 node.inOpenSet = false;
56 node.inClosedSet = false;
57 node.fScore = -1.F;
58 node.gScore = -1.F;
59 }
60 }
61 }
62 }
63
64 Node&
65 Grid::getNode(int row, int col, int orientation)
66 {
67 return data_[((row * cols) + col) * orientations + orientation];
68 }
69
70 void
71 Grid::initialize(int rows, int cols, int orientations, const Costmap3D& costmap)
72 {
74 this->rows = rows;
75 this->cols = cols;
76 this->orientations = orientations;
77
78 // Measure time
80
81 // create the grid with the correct size
82 ARMARX_VERBOSE << "Creating grid";
83
84 data_ = std::make_unique<Node[]>(rows * cols * orientations);
85
86 // intitializing grid
87 for (int r = 0; r < rows; r++)
88 {
89 for (int c = 0; c < cols; c++)
90 {
91 for (int rot_idx = 0; rot_idx < orientations; rot_idx++)
92 {
93 const auto pos = costmap.toPositionGlobal({r, c});
94 const float obstacleDistance = costmap.value_ignore_mask(
96 const auto rotation_deg =
97 costmap.rotationFromIndex(Costmap3D::RotationIndex{rot_idx}).degrees;
98
99 getNode(r, c, rot_idx).initialize(pos, obstacleDistance, rotation_deg);
100 }
101 }
102 }
103
104
105 ARMARX_VERBOSE << "Creating graph";
106
107 ARMARX_CHECK(costmap.params().orientations == orientations);
108
109 // Init successors
110 for (int r = 0; r < rows; r++)
111 {
112 for (int c = 0; c < cols; c++)
113 {
114 for (int rot_idx = 0; rot_idx < orientations; rot_idx++)
115 {
116 Node& candidate = getNode(r, c, rot_idx);
117 if (!fulfillsConstraints(candidate, costmap))
118 {
119 continue;
120 }
121
122 // Add the valid node as successor to all its neighbors
123 for (int nR = -1; nR <= 1; nR++)
124 {
125 for (int nC = -1; nC <= 1; nC++)
126 {
127 const int neighborIndexC = c + nC;
128 const int neighborIndexR = r + nR;
129 if (neighborIndexC < 0 || neighborIndexR < 0 || (nR == 0 && nC == 0))
130 {
131 continue;
132 }
133
134 if (neighborIndexR >= static_cast<int>(rows) ||
135 neighborIndexC >= static_cast<int>(cols))
136 {
137 continue;
138 }
139
140 //grid[neighborIndexR][neighborIndexC][rot_idx]->successors.push_back(candidate);
141
142 for (int nRot = -3; nRot <= 3; nRot++)
143 {
144 int neighborRotIndex = rot_idx + nRot;
145 if (neighborRotIndex < 0)
146 {
147 neighborRotIndex += orientations;
148 }
149 if (neighborRotIndex >= orientations)
150 {
151 neighborRotIndex -= orientations;
152 }
153 getNode(neighborIndexR, neighborIndexC, neighborRotIndex)
154 .successors.emplace_back(&candidate);
155 }
156 }
157 }
158
159 // Add successors by just rotating in place
160 bool enableRotationInPlace =
161 false; // currently has problems with zero-lenght vectors for distance to previous node (would need to be handled separately)
162 for (int nRot = -1; enableRotationInPlace && nRot <= 1; nRot++)
163 {
164 if (nRot == 0)
165 {
166 continue;
167 }
168 int neighborRotIndex = rot_idx + nRot;
169 if (neighborRotIndex < 0)
170 {
171 neighborRotIndex += orientations;
172 }
173 if (neighborRotIndex >= orientations)
174 {
175 neighborRotIndex -= orientations;
176 }
177 getNode(r, c, neighborRotIndex).successors.emplace_back(&candidate);
178 }
179 }
180 }
181 }
182
183 armarx::core::time::DateTime t2 = armarx::core::time::DateTime::Now();
184 ARMARX_VERBOSE << "Grid created in " << (t2 - t1).toMilliSeconds() << " ms";
185 }
186
187 bool
189 {
191
192 // Note: this conversion from deg to index seems unnecessary - maybe we can get rid of it
193 return not costmap.isInCollision(n.position,
194 costmap.closestRotationFromDegrees(n.orientation_deg));
195 }
196
198 costmap3d(costmap3d), params(params)
199 {
200 }
201
202 float
203 AStarPlanner::heuristic(const Node& n1, const Node& n2)
204 {
205 // TODO: Update heuristic and cost functions
206 // Cost function for orientation change should not be 0, otherwise the robot would rotate more than what we want
207 //
208 return std::max(1.F - params.obstacleDistanceWeightFactor, 0.F) *
209 (n1.position - n2.position).norm();
210
211 // maybe we also need to include the orientation in the heuristic?
212 }
213
214 Node&
215 AStarPlanner::closestNode(const core::Pose2D& pose)
216 {
217 float rot_deg = Eigen::Rotation2Df{pose.rotation()}.angle() * 180.F / M_PI;
218 if (rot_deg <= 0.F)
219 {
220 rot_deg += 360.F;
221 }
222 ARMARX_DEBUG << VAROUT(rot_deg);
223
224 const auto vertex = costmap3d.toVertex(pose.translation());
225 const auto rot = costmap3d.closestRotationFromDegrees(rot_deg);
226 ARMARX_DEBUG << "Closest rotation: " << rot.index << " (" << rot.degrees << " deg)";
227
228 const int r = vertex.index.x();
229 const int c = vertex.index.y();
230
233 ARMARX_CHECK_GREATER_EQUAL(rot.index, 0);
234
235 const int rows = static_cast<int>(costmap3d.getSize().x());
236 const int cols = static_cast<int>(costmap3d.getSize().y());
237
238 ARMARX_CHECK_LESS_EQUAL(r, rows - 1);
239 ARMARX_CHECK_LESS_EQUAL(c, cols - 1);
240 ARMARX_CHECK_LESS_EQUAL(rot.index, costmap3d.params().orientations - 1);
241
242 return grid->getNode(static_cast<int>(r), static_cast<int>(c), rot.index);
243 }
244
245 namespace
246 {
247
248 float
249 angleBetween(const Eigen::Vector2f& a, const Eigen::Vector2f& b)
250 {
251 float dotProd = a.dot(b);
252 float magA = a.norm();
253 float magB = b.norm();
254
255 if (magA == 0.0f || magB == 0.0f)
256 {
257 // This is expected if in-place rotations are allowed. However, in other cases this would be unexpected behavior.
258 return 0.F;
259 }
260
261 float cosTheta = dotProd / (magA * magB);
262
263 // Clamp to [-1, 1] to avoid NaNs due to floating-point errors
264 if (cosTheta > 1.0f)
265 cosTheta = 1.0f;
266 if (cosTheta < -1.0f)
267 cosTheta = -1.0f;
268
269 return std::acos(cosTheta); // returns radians
270 }
271
272 float
273 smoothnessCosts(const Node& n1,
274 const Node& n2,
275 const std::optional<Node>& n3,
276 const std::optional<Node>& n4)
277 {
278 float cost = 0;
279
280 auto angle_to_cost = [&](float angle) { return angle * angle; };
281
282 if (n3.has_value())
283 {
284 const Eigen::Vector2f v21 = n1.position - n2.position;
285 const Eigen::Vector2f v23 = n3.value().position - n2.position;
286 float angle = std::abs(angleBetween(v21, -v23));
287 ARMARX_CHECK(angle <= M_PI + 0.001);
288 cost += angle_to_cost(angle);
289 }
290 if (false && n3.has_value() && n4.has_value())
291 {
292 const Eigen::Vector2f v32 = n2.position - n3.value().position;
293 const Eigen::Vector2f v34 = n4.value().position - n3.value().position;
294 float angle = angleBetween(v32, -v34);
295 ARMARX_CHECK(angle <= M_PI + 0.001);
296 cost += angle_to_cost(angle);
297 }
298 return cost;
299 }
300 } // namespace
301
302 std::vector<core::Pose2D>
304 {
306
307 if (grid.has_value())
308 {
309 grid->clear();
310 }
311 else
312 {
313 // initialize grid
314 const auto size = costmap3d.getSize();
315 grid = {size.x(), size.y(), costmap3d.params().orientations, costmap3d};
316 }
317 std::vector<core::Pose2D> result;
318
319 ARMARX_DEBUG << "Setting start node for position " << start.matrix();
320 Node& nodeStart = closestNode(start);
321 ARMARX_INFO << "Start node orientation: " << nodeStart.orientation_deg;
322 ARMARX_INFO << "Start node rotation index: "
323 << costmap3d.closestRotationFromDegrees(nodeStart.orientation_deg).index;
324 ARMARX_CHECK(Grid::fulfillsConstraints(nodeStart, costmap3d)) << "Start node in collision!";
325
326 ARMARX_DEBUG << "Setting goal node for position " << goal.matrix();
327 Node& nodeGoal = closestNode(goal);
328 ARMARX_INFO << "Goal node orientation: " << nodeGoal.orientation_deg;
329 ARMARX_INFO << "Goal node rotation index: "
330 << costmap3d.closestRotationFromDegrees(nodeGoal.orientation_deg).index;
331 ARMARX_CHECK(Grid::fulfillsConstraints(nodeGoal, costmap3d)) << "Goal node in collision!";
332
333 // gScore - (estimated) cost from start node to a given node
334 nodeStart.gScore = 0;
335
336 // fScore - (estimated) cost from the start over the given node to the end (gScore + heuristic)
337 nodeStart.fScore = nodeStart.gScore + heuristic(nodeStart, nodeGoal);
338
339 // open set
340 auto cmp = [&](const Node* left, const Node* right)
341 { return left->fScore > right->fScore; };
342 std::priority_queue<Node*, std::vector<Node*>, decltype(cmp)> openSetPq(cmp);
343 openSetPq.push(&nodeStart);
344 nodeStart.inOpenSet = true;
345
346 bool foundSolution = false;
347 while (!openSetPq.empty())
348 {
349 Node& currentBest = *openSetPq.top();
350 currentBest.inOpenSet = false;
351 openSetPq.pop();
352 if (&currentBest == &nodeGoal)
353 {
354 foundSolution = true;
355 break;
356 }
357
358 currentBest.inClosedSet = true;
359 for (size_t i = 0; i < currentBest.successors.size(); i++)
360 {
361 Node& neighbor = *currentBest.successors[i];
362 if (neighbor.inClosedSet)
363 {
364 continue;
365 }
366
367 Costs cost;
368 try
369 {
370 cost = costs(currentBest, neighbor);
371 }
372 catch (const std::exception& e)
373 {
374 ARMARX_ERROR << "Cost calculation failed for neighbor at position "
375 << neighbor.position.transpose() << " with orientation "
376 << neighbor.orientation_deg << " deg";
377 ARMARX_ERROR << "Current node position: " << currentBest.position.transpose()
378 << " with orientation " << currentBest.orientation_deg << " deg";
379 throw;
380 }
381 const auto pred1 = currentBest.predecessor
382 ? std::make_optional(*currentBest.predecessor)
383 : std::nullopt;
384 const auto pred2 = pred1.has_value()
385 ? pred1->predecessor
386 ? std::make_optional(*(pred1->predecessor))
387 : std::nullopt
388 : std::nullopt;
389 cost.smoothnessCosts = params.smoothnessWeightFactor *
390 smoothnessCosts(neighbor, currentBest, pred1, pred2);
391 float tentativeGScore = currentBest.gScore + cost.combined();
392 if ((not neighbor.inOpenSet) || tentativeGScore < neighbor.gScore)
393 {
394 neighbor.predecessor = std::experimental::make_observer(&currentBest);
395 neighbor.predecessorCosts = cost;
396 neighbor.gScore = tentativeGScore;
397 neighbor.fScore = tentativeGScore + heuristic(neighbor, nodeGoal);
398 if (not neighbor.inOpenSet)
399 {
400 openSetPq.push(&neighbor);
401 neighbor.inOpenSet = true;
402 }
403 }
404 }
405 }
406
407 // Found solution, now retrieve path from goal to start
408 if (foundSolution)
409 {
410 const auto resultNodes = nodeGoal.traversePredecessors();
411 result = resultNodes |
412 ranges::views::transform(
413 [this](const Node* node) noexcept {
414 return costmap3d.globalPose(costmap3d.toVertex(node->position).index,
415 node->orientation_deg);
416 }) |
417 ranges::to_vector;
418 auto predecessorCosts = resultNodes |
419 ranges::views::transform([](const Node* node) noexcept
420 { return node->predecessorCosts; }) |
421 ranges::to_vector;
422 ranges::reverse(predecessorCosts);
423 ARMARX_DEBUG << "Predecessor costs";
424 Costs combinedCosts = {}; // default-initialize to 0
425 for (const auto& c : predecessorCosts)
426 {
427 ARMARX_DEBUG << "------------------";
428 if (not c.has_value())
429 {
430 continue;
431 }
432 ARMARX_DEBUG << "euclidian: " << c->euclidian;
433 ARMARX_DEBUG << "obs_dist: " << c->obstacleProximity;
434 ARMARX_DEBUG << "obs_dist_2: " << c->obstacleProximity2;
435 ARMARX_DEBUG << "ori_diff: " << c->orientationDifference;
436 ARMARX_DEBUG << "forward: " << c->forwardMovement;
437 ARMARX_DEBUG << "smoothness: " << c->smoothnessCosts;
438 combinedCosts = combinedCosts + c.value();
439 }
440
441 ARMARX_INFO << "==================";
442 ARMARX_INFO << "Total costs:";
443 ARMARX_INFO << "euclidian: " << combinedCosts.euclidian;
444 ARMARX_INFO << "obs_dist: " << combinedCosts.obstacleProximity;
445 ARMARX_INFO << "obs_dist_2: " << combinedCosts.obstacleProximity2;
446 ARMARX_INFO << "ori_diff: " << combinedCosts.orientationDifference;
447 ARMARX_INFO << "forward: " << combinedCosts.forwardMovement;
448 ARMARX_INFO << "smoothness: " << combinedCosts.smoothnessCosts;
449 ARMARX_INFO << "==================";
450 }
451
452 // Since the graph was traversed from goal to start, we have to reverse the order
453 ranges::reverse(result);
454
455 return result;
456 }
457
458 Costs
459 AStarPlanner::costs(const Node& n1, const Node& n2) const
460 {
461 const auto vectorDiff = n1.position - n2.position;
462 const float euclideanDistance = vectorDiff.norm();
463
464 // additional costs if
465 const float obstacleDistanceN1 = std::min(n1.obstacleDistance, params.maxObstacleDistance);
466 const float obstacleDistanceN2 = std::min(n2.obstacleDistance, params.maxObstacleDistance);
467
468 // const float obstacleProximityChangeCosts = std::max(obstacleDistanceN1 - obstacleDistanceN2, 0.F);
469 const float obstacleProximityChangeCosts = obstacleDistanceN1 - obstacleDistanceN2;
470
471 // Small note for heuristic:
472 // obstacleProximityChangeCosts can be negative
473
474 // Additional obstacle distance cost (penalty for being near an obstacle for longer than necessary)
475 const float obstacleProximityN2CostsNormalized =
476 (params.maxObstacleDistance - obstacleDistanceN2) / params.maxObstacleDistance;
477
478 // orientation costs
479 const float orientationDist = std::abs(n1.orientation_deg - n2.orientation_deg);
480
481 // prefer to move forward
482 auto pose_n1 = costmap3d.globalPose({0, 0}, n1.orientation_deg);
483 auto pose_n2 = costmap3d.globalPose({0, 0}, n2.orientation_deg);
484 auto ori_vec_n1 = pose_n1.linear() * Eigen::Vector2f::UnitY();
485 auto ori_vec_n2 = pose_n2.linear() * Eigen::Vector2f::UnitY();
486 Eigen::Vector2f ori_vec = ori_vec_n1 + ori_vec_n2;
487 ori_vec.normalize();
488 const Eigen::Vector2f vectorDiff_norm = vectorDiff.normalized();
489 float forward_angle = 0;
490 if (vectorDiff.norm() == 0.F)
491 {
492 ARMARX_DEBUG << "Zero-length vector between nodes, cannot calculate forward movement "
493 "cost. n1 position: "
494 << n1.position.transpose() << ", n2 position: " << n2.position.transpose();
495 ARMARX_DEBUG << "Using 0 instead";
496 }
497 else
498 {
499 forward_angle = std::abs(angleBetween(ori_vec, -vectorDiff_norm));
500 }
501
502 Costs costs = {
503 .euclidian = euclideanDistance,
504 .obstacleProximity = obstacleProximityChangeCosts * params.obstacleDistanceWeightFactor,
505 .obstacleProximity2 =
506 obstacleProximityN2CostsNormalized * params.obstacleDistanceContinuousWeightFactor,
507 .orientationDifference = orientationDist * params.orientationWeightFactor,
508 .forwardMovement = forward_angle * params.forwardWeightFactor,
509 .smoothnessCosts = 0 // TODO set
510 };
511 return costs;
512 }
513
514
515} // namespace armarx::navigation::algorithms::orientation_aware
#define M_PI
Definition MathTools.h:17
#define VAROUT(x)
constexpr T c
Represents a point in time.
Definition DateTime.h:25
static DateTime Now()
Definition DateTime.cpp:51
AStarPlanner(const Costmap3D &costmap, io::AStarWithOrientationParams params)
std::vector< core::Pose2D > plan(const core::Pose2D &start, const core::Pose2D &goal)
core::Pose2D globalPose(const Index &index, const RotationDegrees &rotationDeg) const
Definition Costmap3D.h:108
Rotation rotationFromIndex(RotationIndex index) const
Rotation closestRotationFromDegrees(RotationDegrees degrees) const
Vertex toVertex(const Position &globalPosition) const
Grid(int rows, int cols, int orientations, const Costmap3D &costmap)
static bool fulfillsConstraints(const Node &n, const Costmap3D &costmap)
Node & getNode(int row, int col, int orientation)
A Node can store data to all valid neighbors (successors) and a precessor.
Definition Node.h:55
std::vector< const Node * > traversePredecessors() const
Collects all predecessors in order to generate path to starting point.
Definition Node.cpp:24
void initialize(const Eigen::Vector2f &position, float obstacleDistance, float orientation_deg)
Definition Node.cpp:16
std::experimental::observer_ptr< Node > predecessor
For traversal.
Definition Node.h:72
std::vector< std::experimental::observer_ptr< Node > > successors
All nodes that are adjacent to this one.
Definition Node.h:70
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_LESS_EQUAL(lhs, rhs)
This macro evaluates whether lhs is less or equal (<=) rhs and if it turns out to be false it will th...
#define ARMARX_CHECK_GREATER_EQUAL(lhs, rhs)
This macro evaluates whether lhs is greater or equal (>=) rhs and if it turns out to be false it will...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
Eigen::Isometry2f Pose2D
Definition basic_types.h:34
This file offers overloads of toIce() and fromIce() functions for STL container types.
float euclideanDistance(IteratorType1 first1, IteratorType1 last1, IteratorType2 first2)
Returns the euclidean distance.
Definition Metrics.h:104
observer_ptr< _Tp > make_observer(_Tp *__p) noexcept
double norm(const Point &a)
Definition point.hpp:102
double angle(const Point &a, const Point &b, const Point &c)
Definition point.hpp:109
int orientations
How many orientations of the robot each cell contains.
Definition Costmap3D.h:38
#define ARMARX_TRACE
Definition trace.h:77