-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathEnvironmentXYZTheta.cpp
1430 lines (1210 loc) · 54 KB
/
EnvironmentXYZTheta.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include "EnvironmentXYZTheta.hpp"
#include <sbpl/planners/planner.h>
#include <sbpl/utils/mdpconfig.h>
#include <base/Pose.hpp>
#include <base/Spline.hpp>
#include <fstream>
#include <vizkit3d_debug_drawings/DebugDrawing.hpp>
#include <vizkit3d_debug_drawings/DebugDrawingColors.hpp>
#include "PathStatistic.hpp"
#include "Dijkstra.hpp"
#include <limits>
#include <base-logging/Logging.hpp>
using namespace std;
using namespace sbpl_spline_primitives;
using trajectory_follower::SubTrajectory;
using trajectory_follower::DriveMode;
namespace ugv_nav4d
{
#define oassert(val) \
if(!(val)) \
{\
LOG_ERROR_S << #val; \
LOG_ERROR_S << __FILE__ << ": " << __LINE__; \
throw std::runtime_error("meeeeh"); \
}
EnvironmentXYZTheta::EnvironmentXYZTheta(std::shared_ptr<MLGrid> mlsGrid,
const traversability_generator3d::TraversabilityConfig& travConf,
const SplinePrimitivesConfig& primitiveConfig,
const Mobility& mobilityConfig) :
travGen(travConf), obsGen(travConf)
, mlsGrid(mlsGrid)
, availableMotions(primitiveConfig, mobilityConfig)
, startThetaNode(nullptr)
, startXYZNode(nullptr)
, goalThetaNode(nullptr)
, goalXYZNode(nullptr)
, obstacleStartNode(nullptr)
, travConf(travConf)
, primitiveConfig(primitiveConfig)
, mobilityConfig(mobilityConfig)
{
numAngles = primitiveConfig.numAngles;
travGen.setMLSGrid(mlsGrid);
obsGen.setMLSGrid(mlsGrid);
searchGrid.setResolution(Eigen::Vector2d(travConf.gridResolution, travConf.gridResolution));
searchGrid.extend(travGen.getTraversabilityMap().getNumCells());
robotHalfSize << travConf.robotSizeX / 2, travConf.robotSizeY / 2, travConf.robotHeight/2;
if(mlsGrid)
{
availableMotions.computeMotions(mlsGrid->getResolution().x(), travConf.gridResolution);
}
}
void EnvironmentXYZTheta::clear()
{
//clear the search grid
for(maps::grid::LevelList<XYZNode *> &l : searchGrid)
{
for(XYZNode *n : l)
{
for(auto &tn : n->getUserData().thetaToNodes)
{
delete tn.second;
}
delete n;
}
l.clear();
}
searchGrid.clear();
idToHash.clear();
travNodeIdToDistance.clear();
startThetaNode = nullptr;
startXYZNode = nullptr;
goalThetaNode = nullptr;
goalXYZNode = nullptr;
for(int *p: StateID2IndexMapping)
{
delete[] p;
}
StateID2IndexMapping.clear();
}
EnvironmentXYZTheta::~EnvironmentXYZTheta()
{
clear();
}
void EnvironmentXYZTheta::setInitialPatch(const Eigen::Affine3d& ground2Mls, double patchRadius)
{
travGen.setInitialPatch(ground2Mls, patchRadius);
obsGen.setInitialPatch(ground2Mls, patchRadius);
}
void EnvironmentXYZTheta::updateMap(shared_ptr< ugv_nav4d::EnvironmentXYZTheta::MLGrid > mlsGrid)
{
if(this->mlsGrid && this->mlsGrid->getResolution() != mlsGrid->getResolution())
throw std::runtime_error("EnvironmentXYZTheta::updateMap : Error got MLSMap with different resolution");
if(!this->mlsGrid)
{
availableMotions.computeMotions(mlsGrid->getResolution().x(), travConf.gridResolution);
}
travGen.setMLSGrid(mlsGrid);
obsGen.setMLSGrid(mlsGrid);
this->mlsGrid = mlsGrid;
clear();
}
EnvironmentXYZTheta::XYZNode* EnvironmentXYZTheta::createNewXYZState(traversability_generator3d::TravGenNode* travNode)
{
XYZNode *xyzNode = new XYZNode(travNode->getHeight(), travNode->getIndex());
xyzNode->getUserData().travNode = travNode;
searchGrid.at(travNode->getIndex()).insert(xyzNode);
return xyzNode;
}
EnvironmentXYZTheta::ThetaNode* EnvironmentXYZTheta::createNewStateFromPose(const std::string &name, const Eigen::Vector3d& pos, double theta, XYZNode **xyzBackNode)
{
traversability_generator3d::TravGenNode *travNode = travGen.generateStartNode(pos);
if(!travNode)
{
LOG_INFO_S << "Could not generate Node at pos";
return nullptr;
}
//check if intitial patch is unknown
if(!travNode->isExpanded())
{
if(!travGen.expandNode(travNode))
{
LOG_INFO_S << "createNewStateFromPose: Error: " << name << " Pose " << pos.transpose() << " is not traversable";
return nullptr;
}
travNode->setNotExpanded();
}
XYZNode *xyzNode = createNewXYZState(travNode);
DiscreteTheta thetaD(theta, numAngles);
if(xyzBackNode)
*xyzBackNode = xyzNode;
return createNewState(thetaD, xyzNode);
}
bool EnvironmentXYZTheta::obstacleCheck(const maps::grid::Vector3d& pos, double theta,
const ObstacleMapGenerator3D& obsGen,
const traversability_generator3d::TraversabilityConfig& travConf,
const SplinePrimitivesConfig& splineConf,
const std::string& nodeName)
{
maps::grid::Index idxObstNode;
if(!obsGen.getTraversabilityMap().toGrid(pos, idxObstNode))
{
LOG_INFO_S << "Error " << nodeName << " is outside of obstacle map ";
return false;
}
traversability_generator3d::TravGenNode* obstacleNode = obsGen.findMatchingTraversabilityPatchAt(idxObstNode, pos.z());
if(!obstacleNode)
{
LOG_INFO_S << "Error, could not find matching obstacle node for " << nodeName;
return false;
}
if (obstacleNode->getType() != ::maps::grid::TraversabilityNodeBase::TRAVERSABLE)
{
return false;
}
if (usePathStatistics){
PathStatistic stats(travConf);
std::vector<base::Pose2D> poses;
std::vector<const traversability_generator3d::TravGenNode*> path;
path.push_back(obstacleNode);
const Eigen::Vector3d centeredPos = obstacleNode->getPosition(obsGen.getTraversabilityMap());
//NOTE theta needs to be discretized because the planner uses discrete theta internally everywhere.
// If we do not discretize here, external calls and internal calls will have different results for the same pose input
DiscreteTheta discTheta(theta, splineConf.numAngles);
poses.push_back(base::Pose2D(centeredPos.topRows(2), discTheta.getRadian()));
stats.calculateStatistics(path, poses, obsGen.getTraversabilityMap(), "ugv_nav4d_" + nodeName + "Box");
if(stats.getRobotStats().getNumObstacles() || stats.getRobotStats().getNumFrontiers())
{
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::COMPLEX_DRAWING([&]()
{
const std::string drawName("ugv_nav4d_obs_check_fail_" + nodeName);
V3DD::CLEAR_DRAWING(drawName);
V3DD::DRAW_WIREFRAME_BOX(drawName, pos, Eigen::Quaterniond(Eigen::AngleAxisd(discTheta.getRadian(), Eigen::Vector3d::UnitZ())), Eigen::Vector3d(travConf.robotSizeX, travConf.robotSizeY, travConf.robotHeight), V3DD::Color::red);
});
#endif
LOG_INFO_S << "Num obstacles: " << stats.getRobotStats().getNumObstacles();
LOG_INFO_S << "Error: " << nodeName << " inside obstacle";
return false;
}
}
return true;
}
bool EnvironmentXYZTheta::checkStartGoalNode(const string& name, traversability_generator3d::TravGenNode *node, double theta)
{
//check for collisions NOTE has to be done after expansion
maps::grid::Vector3d nodePos;
travGen.getTraversabilityMap().fromGrid(node->getIndex(), nodePos, node->getHeight(), false);
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::COMPLEX_DRAWING([&]()
{
const std::string drawName("ugv_nav4d_check_start_goal_" + name);
V3DD::CLEAR_DRAWING(drawName);
V3DD::DRAW_WIREFRAME_BOX(drawName, nodePos, Eigen::Quaterniond(Eigen::AngleAxisd(theta, Eigen::Vector3d::UnitZ())), Eigen::Vector3d(travConf.robotSizeX, travConf.robotSizeY, travConf.robotHeight), V3DD::Color::red);
});
#endif
return obstacleCheck(nodePos, theta, obsGen, travConf, primitiveConfig, name);
}
void EnvironmentXYZTheta::setGoal(const Eigen::Vector3d& goalPos, double theta)
{
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::CLEAR_DRAWING("ugv_nav4d_env_goalPos");
V3DD::DRAW_ARROW("ugv_nav4d_env_goalPos", goalPos, base::Quaterniond(Eigen::AngleAxisd(M_PI, base::Vector3d::UnitX())),
base::Vector3d(1,1,1), V3DD::Color::red);
#endif
LOG_INFO_S << "GOAL IS: " << goalPos.transpose();
if(!startXYZNode)
throw std::runtime_error("Error, start needs to be set before goal");
goalThetaNode = createNewStateFromPose("goal", goalPos, theta, &goalXYZNode);
if(!goalThetaNode)
{
throw StateCreationFailed("Failed to create goal state");
}
const auto nodeType = goalXYZNode->getUserData().travNode->getType();
if(nodeType != maps::grid::TraversabilityNodeBase::TRAVERSABLE) {
throw std::runtime_error("Error, goal has to be a traversable patch");
}
if(travConf.enableInclineLimitting)
{
if(!checkOrientationAllowed(goalXYZNode->getUserData().travNode, theta))
{
LOG_INFO_S << "Goal orientation not allowed due to slope";
throw OrientationNotAllowed("Goal orientation not allowed due to slope");
}
}
//NOTE If we want to precompute the heuristic (precomputeCost()) we need to expand
// the whole travmap beforehand.
//check goal position
if(!checkStartGoalNode("goal", goalXYZNode->getUserData().travNode, goalThetaNode->theta.getRadian()))
{
LOG_INFO_S << "goal position is invalid";
throw ObstacleCheckFailed("goal position is invalid");
}
try {
precomputeCost();
LOG_INFO_S << "Heuristic computed";
}
catch(const std::runtime_error& ex){
throw ex;
}
//draw greedy path
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::COMPLEX_DRAWING([&]()
{
V3DD::CLEAR_DRAWING("ugv_nav4d_greedyPath");
traversability_generator3d::TravGenNode* nextNode = startXYZNode->getUserData().travNode;
traversability_generator3d::TravGenNode* goal = goalXYZNode->getUserData().travNode;
while(nextNode != goal)
{
maps::grid::Vector3d pos;
travGen.getTraversabilityMap().fromGrid(nextNode->getIndex(), pos, nextNode->getHeight(), false);
V3DD::DRAW_CYLINDER("ugv_nav4d_greedyPath", pos, base::Vector3d(0.03, 0.03, 0.3), V3DD::Color::yellow);
double minCost = std::numeric_limits< double >::max();
bool foundNextNode = false;
for(maps::grid::TraversabilityNodeBase* node : nextNode->getConnections())
{
traversability_generator3d::TravGenNode* travNode = static_cast<traversability_generator3d::TravGenNode*>(node);
const double cost = travNodeIdToDistance[travNode->getUserData().id].distToGoal;
if(cost < minCost)
{
minCost = cost;
nextNode = travNode;
foundNextNode = true;
}
}
if (!foundNextNode) {
LOG_INFO_S << "nextNode has no connection";
break;
}
}
});
#endif
}
void EnvironmentXYZTheta::expandMap(const std::vector<Eigen::Vector3d>& positions)
{
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::COMPLEX_DRAWING([&]()
{
V3DD::CLEAR_DRAWING("ugv_nav4d_expandStarts");
for(const Eigen::Vector3d& pos : positions)
{
V3DD::DRAW_ARROW("ugv_nav4d_expandStarts", pos, base::Quaterniond(Eigen::AngleAxisd(M_PI, base::Vector3d::UnitX())),
base::Vector3d(1,1,1), V3DD::Color::cyan);
}
});
#endif
travGen.expandAll(positions);
obsGen.expandAll(positions);
}
void EnvironmentXYZTheta::setStart(const Eigen::Vector3d& startPos, double theta)
{
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::CLEAR_DRAWING("ugv_nav4d_env_startPos");
V3DD::DRAW_ARROW("ugv_nav4d_env_startPos", startPos, base::Quaterniond(Eigen::AngleAxisd(M_PI, base::Vector3d::UnitX())),
base::Vector3d(1,1,1), V3DD::Color::blue);
#endif
LOG_INFO_S << "START IS: " << startPos.transpose();
startThetaNode = createNewStateFromPose("start", startPos, theta, &startXYZNode);
if(!startThetaNode)
throw StateCreationFailed("Failed to create start state");
obstacleStartNode = obsGen.generateStartNode(startPos);
if(!obstacleStartNode)
{
LOG_INFO_S << "Could not generate obstacle node at start pos";
throw ObstacleCheckFailed("Could not generate obstacle node at start pos");
}
//check start position
if(!checkStartGoalNode("start", startXYZNode->getUserData().travNode, startThetaNode->theta.getRadian()))
{
LOG_INFO_S<< "Start position is invalid";
throw ObstacleCheckFailed("Start position inside obstacle");
}
}
void EnvironmentXYZTheta::SetAllPreds(CMDPSTATE* state)
{
//implement this if the planner needs access to predecessors
SBPL_ERROR("ERROR in EnvNAV2D... function: SetAllPreds is undefined\n");
throw EnvironmentXYZThetaException("SetAllPreds() not implemented");
}
void EnvironmentXYZTheta::SetAllActionsandAllOutcomes(CMDPSTATE* state)
{
SBPL_ERROR("ERROR in EnvNAV2D... function: SetAllActionsandAllOutcomes is undefined\n");
throw EnvironmentXYZThetaException("SetAllActionsandAllOutcomes() not implemented");
}
int EnvironmentXYZTheta::GetFromToHeuristic(int FromStateID, int ToStateID)
{
//sbpl never calls this
throw std::runtime_error("GetFromToHeuristic not implemented");
}
maps::grid::Vector3d EnvironmentXYZTheta::getStatePosition(const int stateID) const
{
const Hash &sourceHash(idToHash[stateID]);
const XYZNode *node = sourceHash.node;
maps::grid::Vector3d ret;
travGen.getTraversabilityMap().fromGrid(node->getIndex(), ret, node->getHeight());
return ret;
}
const Motion& EnvironmentXYZTheta::getMotion(const int fromStateID, const int toStateID)
{
int cost = -1;
size_t motionId = 0;
vector<int> successStates;
vector<int> successStateCosts;
vector<size_t> motionIds;
GetSuccs(fromStateID, &successStates, &successStateCosts, motionIds);
for(size_t i = 0; i < successStates.size(); i++)
{
if(successStates[i] == toStateID)
{
if(cost == -1 || cost > successStateCosts[i])
{
cost = successStateCosts[i];
motionId = motionIds[i];
}
}
}
if(cost == -1)
throw std::runtime_error("Internal Error: No matching motion for output path found");
return availableMotions.getMotion(motionId);
}
int EnvironmentXYZTheta::GetGoalHeuristic(int stateID)
{
// the heuristic distance has been calculated beforehand. Here it is just converted to
// travel time.
const Hash &sourceHash(idToHash[stateID]);
const XYZNode *sourceNode = sourceHash.node;
const traversability_generator3d::TravGenNode* travNode = sourceNode->getUserData().travNode;
const ThetaNode *sourceThetaNode = sourceHash.thetaNode;
if(travNode->getType() != maps::grid::TraversabilityNodeBase::TRAVERSABLE && travNode->getType() != maps::grid::TraversabilityNodeBase::FRONTIER)
{
std::map<int, std::string> numToTravType;
numToTravType[maps::grid::TraversabilityNodeBase::OBSTACLE] = "OBSTACLE";
numToTravType[maps::grid::TraversabilityNodeBase::TRAVERSABLE] = "TRAVERSABLE";
numToTravType[maps::grid::TraversabilityNodeBase::UNKNOWN] = "UNKNOWN";
numToTravType[maps::grid::TraversabilityNodeBase::HOLE] = "HOLE";
numToTravType[maps::grid::TraversabilityNodeBase::UNSET] = "UNSET";
numToTravType[maps::grid::TraversabilityNodeBase::FRONTIER] = "FRONTIER";
//throw std::runtime_error("tried to get heuristic for " + numToTravType[travNode->getType()] + " patch. StateID: " + std::to_string(stateID));
return std::numeric_limits<int>::max();
}
const double sourceToGoalDist = travNodeIdToDistance[travNode->getUserData().id].distToGoal;
const double timeTranslation = sourceToGoalDist / mobilityConfig.translationSpeed;
//for point turns the translational time is zero, however turning still takes time
const double timeRotation = sourceThetaNode->theta.shortestDist(goalThetaNode->theta).getRadian() / mobilityConfig.rotationSpeed;
//scale by costScaleFactor to avoid loss of precision before converting to int
const double maxTime = std::max(timeTranslation, timeRotation);
// try to avoid overflow by skipping scaling for already large values (scaling is only useful for small values)
int result = maxTime >= 10000000 ? maxTime : maxTime * Motion::costScaleFactor;
if(result < 0)
{
LOG_INFO_S << sourceToGoalDist;
LOG_INFO_S << stateID;
LOG_INFO_S << mobilityConfig.translationSpeed;
LOG_INFO_S << timeTranslation;
LOG_INFO_S << sourceThetaNode->theta.shortestDist(goalThetaNode->theta).getRadian();
LOG_INFO_S << mobilityConfig.rotationSpeed;
LOG_INFO_S << timeRotation;
LOG_INFO_S << result;
LOG_INFO_S << travNode->getUserData().id;
LOG_INFO_S << travNode->getType();
//throw std::runtime_error("Goal heuristic < 0");
LOG_INFO_S<< "Overflow while computing goal heuristic!";
result = std::numeric_limits<int>::max();
}
oassert(result >= 0);
return result;
}
void EnvironmentXYZTheta::enablePathStatistics(bool enable){
usePathStatistics = enable;
}
int EnvironmentXYZTheta::GetStartHeuristic(int stateID)
{
const Hash &targetHash(idToHash[stateID]);
const XYZNode *targetNode = targetHash.node;
const traversability_generator3d::TravGenNode* travNode = targetNode->getUserData().travNode;
const ThetaNode *targetThetaNode = targetHash.thetaNode;
const double startToTargetDist = travNodeIdToDistance[travNode->getUserData().id].distToStart;
const double timeTranslation = startToTargetDist / mobilityConfig.translationSpeed;
double timeRotation = startThetaNode->theta.shortestDist(targetThetaNode->theta).getRadian() / mobilityConfig.rotationSpeed;
const int result = floor(std::max(timeTranslation, timeRotation) * Motion::costScaleFactor);
oassert(result >= 0);
return result;
}
bool EnvironmentXYZTheta::InitializeEnv(const char* sEnvFile)
{
return true;
}
bool EnvironmentXYZTheta::InitializeMDPCfg(MDPConfig* MDPCfg)
{
if(!goalThetaNode || !startThetaNode)
return false;
//initialize MDPCfg with the start and goal ids
MDPCfg->goalstateid = goalThetaNode->id;
MDPCfg->startstateid = startThetaNode->id;
return true;
}
EnvironmentXYZTheta::ThetaNode *EnvironmentXYZTheta::createNewState(const DiscreteTheta &curTheta, XYZNode *curNode)
{
ThetaNode *newNode = new ThetaNode(curTheta);
newNode->id = idToHash.size();
Hash hash(curNode, newNode);
idToHash.push_back(hash);
curNode->getUserData().thetaToNodes.insert(make_pair(curTheta, newNode));
//this structure need to be extended for every new state that is added.
//Is seems it is later on filled in by the planner.
//insert into and initialize the mappings
int* entry = new int[NUMOFINDICES_STATEID2IND];
StateID2IndexMapping.push_back(entry);
for (int i = 0; i < NUMOFINDICES_STATEID2IND; i++) {
StateID2IndexMapping[newNode->id][i] = -1;
}
return newNode;
}
traversability_generator3d::TravGenNode *EnvironmentXYZTheta::movementPossible(traversability_generator3d::TravGenNode *fromTravNode, const maps::grid::Index &fromIdx, const maps::grid::Index &toIdx)
{
if(toIdx == fromIdx)
return fromTravNode;
//get trav node associated with the next index
traversability_generator3d::TravGenNode *targetNode = fromTravNode->getConnectedNode(toIdx);
if(!targetNode)
{
//FIXME this should never happen but it did happen in the past and I have no idea why
// needs investigation!
LOG_INFO_S<< "movement not possible. nodes not conncted";
return nullptr;
}
if(!checkExpandTreadSafe(targetNode))
{
return nullptr;
}
//NOTE this check cannot be done before checkExpandTreadSafe because the type will be determined
// during the expansion. Beforehand the type is undefined
if(targetNode->getType() != maps::grid::TraversabilityNodeBase::TRAVERSABLE)
{
// LOG_INFO_S<< "movement not possible. targetnode not traversable";
return nullptr;
}
return targetNode;
}
bool EnvironmentXYZTheta::checkExpandTreadSafe(traversability_generator3d::TravGenNode * node)
{
if(node->isExpanded())
{
return true;
}
bool result = true;
#pragma omp critical(checkExpandTreadSafe)
{
if(!node->isExpanded())
{
result = travGen.expandNode(node);
}
}
return result;
}
void EnvironmentXYZTheta::GetSuccs(int SourceStateID, vector< int >* SuccIDV, vector< int >* CostV)
{
std::vector<size_t> motionId;
GetSuccs(SourceStateID, SuccIDV, CostV, motionId);
}
traversability_generator3d::TravGenNode * EnvironmentXYZTheta::checkTraversableHeuristic(const maps::grid::Index sourceIndex, traversability_generator3d::TravGenNode *sourceNode,
const Motion &motion, const maps::grid::TraversabilityMap3d<traversability_generator3d::TravGenNode *> &trMap)
{
traversability_generator3d::TravGenNode *travNode = sourceNode;
maps::grid::Index curIndex = sourceIndex;
for(const PoseWithCell &diff : motion.intermediateStepsTravMap)
{
//diff is always a full offset to the start position
const maps::grid::Index newIndex = sourceIndex + diff.cell;
travNode = movementPossible(travNode, curIndex, newIndex);
if(!travNode)
{
return nullptr;
}
curIndex = newIndex;
}
return travNode;
}
void EnvironmentXYZTheta::GetSuccs(int SourceStateID, vector< int >* SuccIDV, vector< int >* CostV, vector< size_t >& motionIdV)
{
SuccIDV->clear();
CostV->clear();
motionIdV.clear();
const Hash &sourceHash(idToHash[SourceStateID]);
const XYZNode *const sourceNode = sourceHash.node;
const ThetaNode *const sourceThetaNode = sourceHash.thetaNode;
traversability_generator3d::TravGenNode *sourceTravNode = sourceNode->getUserData().travNode;
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::COMPLEX_DRAWING([&]()
{
const traversability_generator3d::TravGenNode* node = sourceNode->getUserData().travNode;
Eigen::Vector3d pos((node->getIndex().x() + 0.5) * travConf.gridResolution,
(node->getIndex().y() + 0.5) * travConf.gridResolution,
node->getHeight());
pos = mlsGrid->getLocalFrame().inverse(Eigen::Isometry) * pos;
V3DD::DRAW_WIREFRAME_BOX("ugv_nav4d_successors", pos, base::Vector3d(mlsGrid->getResolution().x() / 2.0, mlsGrid->getResolution().y() / 2.0,
0.05), V3DD::Color::blue);
});
#endif
if(!sourceTravNode->isExpanded())
{
if(!travGen.expandNode(sourceTravNode))
{
//expansion failed, current node is not driveable -> there are not successors to this state
LOG_INFO_S<< "GetSuccs: current node not expanded and not expandable";
return;
}
}
Eigen::Vector3d sourcePosWorld;
travGen.getTraversabilityMap().fromGrid(sourceNode->getIndex(), sourcePosWorld, sourceTravNode->getHeight(), false);
traversability_generator3d::TravGenNode *sourceObstacleNode = findObstacleNode(sourceTravNode);
assert(sourceObstacleNode);
const auto& motions = availableMotions.getMotionForStartTheta(sourceThetaNode->theta);
//dynamic scheduling is choosen because the iterations have vastly different runtime
//due to the different sanity checks
//the chunk size (5) was chosen to reduce dynamic scheduling overhead.
//**No** tests have been done to verify whether 5 is a good value or not!
//#pragma omp parallel for schedule(dynamic, 5)
#pragma omp parallel for schedule(auto)
for(size_t i = 0; i < motions.size(); ++i)
{
//check that the motion is traversable (without collision checks) and find the goal node of the motion
const ugv_nav4d::Motion &motion(motions[i]);
traversability_generator3d::TravGenNode *goalTravNode = checkTraversableHeuristic(sourceNode->getIndex(), sourceNode->getUserData().travNode, motions[i], travGen.getTraversabilityMap());
if(!goalTravNode)
{
//at least one node on the path is not traversable
continue;
}
//check motion path on obstacle map
std::vector<const traversability_generator3d::TravGenNode*> nodesOnObstPath;
std::vector<base::Pose2D> posesOnObstPath;
maps::grid::Index curObstIdx = sourceObstacleNode->getIndex();
traversability_generator3d::TravGenNode *obstNode = sourceObstacleNode;
bool intermediateStepsOk = true;
for(const PoseWithCell &diff : motion.intermediateStepsObstMap)
{
//diff is always a full offset to the start position
const maps::grid::Index newIndex = sourceObstacleNode->getIndex() + diff.cell;
obstNode = movementPossible(obstNode, curObstIdx, newIndex);
nodesOnObstPath.push_back(obstNode);
base::Pose2D curPose = diff.pose;
curPose.position += sourcePosWorld.head<2>();
posesOnObstPath.push_back(curPose);
if(!obstNode)
{
intermediateStepsOk = false;
break;
}
if(travConf.enableInclineLimitting)
{
if(!checkOrientationAllowed(obstNode, diff.pose.orientation))
{
intermediateStepsOk = false;
break;
}
}
curObstIdx = newIndex;
}
//no way from start to end on obstacle map
if(!intermediateStepsOk)
continue;
if (usePathStatistics){
PathStatistic statistic(travConf);
if(!statistic.isPathFeasible(nodesOnObstPath, posesOnObstPath, getObstacleMap()))
{
continue;
}
}
//goal from source to the end of the motion was valid
XYZNode *successXYNode = nullptr;
ThetaNode *successthetaNode = nullptr;
//WARNING This becomes a critical section if several motion primitives
// share the same finalPos.
// As long as this is not the case this section should be save.
const maps::grid::Index finalPos(sourceNode->getIndex() + maps::grid::Index(motion.xDiff,motion.yDiff));
#pragma omp critical(searchGridAccess)
{
const auto &candidateMap = searchGrid.at(finalPos);
if(goalTravNode->getIndex() != finalPos)
throw std::runtime_error("Internal error, indexes do not match");
XYZNode searchTmp(goalTravNode->getHeight(), goalTravNode->getIndex());
//this works, as the equals check is on the height, not the node itself
auto it = candidateMap.find(&searchTmp);
if(it != candidateMap.end())
{
//found a node with a matching height
successXYNode = *it;
}
else
{
successXYNode = createNewXYZState(goalTravNode); //modifies searchGrid at travNode->getIndex()
}
}
#pragma omp critical(thetaToNodesAccess)
{
const auto &thetaMap(successXYNode->getUserData().thetaToNodes);
auto thetaCandidate = thetaMap.find(motion.endTheta);
if(thetaCandidate != thetaMap.end())
{
successthetaNode = thetaCandidate->second;
}
else
{
successthetaNode = createNewState(motion.endTheta, successXYNode);
}
}
double cost = 0;
switch(travConf.slopeMetric)
{
case traversability_generator3d::SlopeMetric::AVG_SLOPE:
{
double avgSlope = 0;
if(nodesOnObstPath.size() > 0)
{
avgSlope = getAvgSlope(nodesOnObstPath);
}
else
{
//This happens on point turns as they have no intermediate steps
avgSlope = sourceTravNode->getUserData().slope;
}
const double slopeFactor = avgSlope * travConf.slopeMetricScale;
cost = motion.baseCost + motion.baseCost * slopeFactor;
LOG_INFO_S<< "cost: " << cost << ", baseCost: " << motion.baseCost << ", slopeFactor: " << slopeFactor;
break;
}
case traversability_generator3d::SlopeMetric::MAX_SLOPE:
{
double maxSlope = 0;
if(nodesOnObstPath.size() > 0)
{
maxSlope = getMaxSlope(nodesOnObstPath);
}
else
{
//This happens on point turns as they have no intermediate steps
maxSlope = sourceTravNode->getUserData().slope;
}
const double slopeFactor = maxSlope * travConf.slopeMetricScale;
cost = motion.baseCost + motion.baseCost * slopeFactor;
break;
}
case traversability_generator3d::SlopeMetric::TRIANGLE_SLOPE:
{
//assume that the motion is a straight line, extrapolate into third dimension
//by projecting onto a plane that connects start and end cell.
const double heightDiff = std::abs(sourceNode->getHeight() - successXYNode->getHeight());
//not perfect but probably more exact than the slope factors above
const double approxMotionLen3D = std::sqrt(std::pow(motion.translationlDist, 2) + std::pow(heightDiff, 2));
assert(approxMotionLen3D >= motion.translationlDist);//due to triangle inequality
const double translationalVelocity = mobilityConfig.translationSpeed;
cost = Motion::calculateCost(approxMotionLen3D, motion.angularDist, translationalVelocity,
mobilityConfig.rotationSpeed, motion.costMultiplier);
break;
}
case traversability_generator3d::SlopeMetric::NONE:
cost = motion.baseCost;
break;
default:
throw std::runtime_error("unknown slope metric selected");
}
if (usePathStatistics){
PathStatistic statistic(travConf);
if(statistic.getBoundaryStats().getNumObstacles())
{
const double outer_radius = travConf.costFunctionDist;
double minDistToRobot = statistic.getBoundaryStats().getMinDistToObstacles();
minDistToRobot = std::min(outer_radius, minDistToRobot);
double impactFactor = (outer_radius - minDistToRobot) / outer_radius;
oassert(impactFactor < 1.001 && impactFactor >= 0);
cost += cost * impactFactor;
}
if(statistic.getBoundaryStats().getNumFrontiers())
{
const double outer_radius = travConf.costFunctionDist;
double minDistToRobot = statistic.getBoundaryStats().getMinDistToFrontiers();
minDistToRobot = std::min(outer_radius, minDistToRobot);
double impactFactor = (outer_radius - minDistToRobot) / outer_radius;
oassert(impactFactor < 1.001 && impactFactor >= 0);
cost += cost * impactFactor;
}
}
oassert(cost <= std::numeric_limits<int>::max() && cost >= std::numeric_limits< int >::min());
oassert(int(cost) >= motion.baseCost);
oassert(motion.baseCost > 0);
const int iCost = (int)cost;
#pragma omp critical(updateData)
{
SuccIDV->push_back(successthetaNode->id);
CostV->push_back(iCost);
motionIdV.push_back(motion.id);
//####BEGIN DEBUG BLOCK!
{
const Hash &sourceHashh(idToHash[successthetaNode->id]);
const XYZNode *sourceNodeh = sourceHashh.node;
const traversability_generator3d::TravGenNode* travNodeh = sourceNodeh->getUserData().travNode;
if(travNodeh->getType() != maps::grid::TraversabilityNodeBase::TRAVERSABLE)
{
throw std::runtime_error("In GetSuccs() returned id for non-traversable patch");
}
}
//####END DEBUG BLOCK!!!
}
}
}
bool EnvironmentXYZTheta::checkOrientationAllowed(const traversability_generator3d::TravGenNode* node,
const base::Orientation2D& orientationRad) const
{
//otherwise something went wrong when generating the map
assert(node->getUserData().allowedOrientations.size() > 0);
const base::Angle orientation = base::Angle::fromRad(orientationRad);
bool isInside = false;
for(const base::AngleSegment& segment : node->getUserData().allowedOrientations)
{
if(segment.isInside(orientation))
{
isInside = true;
break;
}
}
return isInside;
}
void EnvironmentXYZTheta::GetPreds(int TargetStateID, vector< int >* PredIDV, vector< int >* CostV)
{
SBPL_ERROR("ERROR in EnvNAV2D... function: GetPreds is undefined\n");
throw EnvironmentXYZThetaException("GetPreds() not implemented");
}
int EnvironmentXYZTheta::SizeofCreatedEnv()
{
return static_cast<int>(idToHash.size());
}
void EnvironmentXYZTheta::PrintEnv_Config(FILE* fOut)
{
throw EnvironmentXYZThetaException("PrintEnv_Config() not implemented");
}
void EnvironmentXYZTheta::PrintState(int stateID, bool bVerbose, FILE* fOut)
{
const Hash &hash(idToHash[stateID]);
std::stringbuf buffer;
std::ostream os (&buffer);
os << "State "<< stateID << " coordinate " << hash.node->getIndex().transpose() << " " << hash.node->getHeight() << " Theta " << hash.thetaNode->theta << endl;
if(fOut)
fprintf(fOut, "%s", buffer.str().c_str());
else
LOG_INFO_S<< buffer.str();
}
vector<Motion> EnvironmentXYZTheta::getMotions(const vector< int >& stateIDPath)
{
vector<Motion> result;
if(stateIDPath.size() >= 2)
{
for(size_t i = 0; i < stateIDPath.size() -1; ++i)
{
result.push_back(getMotion(stateIDPath[i], stateIDPath[i + 1]));
}
}
return result;
}
void EnvironmentXYZTheta::getTrajectory(const vector<int>& stateIDPath,
vector<SubTrajectory>& result,
bool setZToZero, const Eigen::Vector3d &startPos,
const Eigen::Vector3d &goalPos, const double& goalHeading, const Eigen::Affine3d &plan2Body)
{
if(stateIDPath.size() < 2)
return;
result.clear();
base::Trajectory curPart;
#ifdef ENABLE_DEBUG_DRAWINGS
V3DD::CLEAR_DRAWING("ugv_nav4d_trajectory");
#endif
int indexOfMotionToUpdate{stateIDPath.size()-2};
const Motion& finalMotion = getMotion(stateIDPath[stateIDPath.size()-2], stateIDPath[stateIDPath.size()-1]);
if (finalMotion.type == Motion::Type::MOV_POINTTURN && stateIDPath.size() > 2){ //assuming that there are no consecutive point turns motion at the end of a planned trajectory
indexOfMotionToUpdate = stateIDPath.size()-3;
}
bool goal_position_updated = false;
Eigen::Vector3d start = startPos;
for(size_t i = 0; i < stateIDPath.size() - 1; ++i)
{
const Motion& curMotion = getMotion(stateIDPath[i], stateIDPath[i+1]);
const Hash &startHash(idToHash[stateIDPath[i]]);
const maps::grid::Index startIndex(startHash.node->getIndex());
maps::grid::Index lastIndex = startIndex;
traversability_generator3d::TravGenNode *curNode = startHash.node->getUserData().travNode;
std::vector<base::Vector3d> positions;
for(const CellWithPoses &cwp : curMotion.fullSplineSamples)
{
maps::grid::Index curIndex = startIndex + cwp.cell;
if(curIndex != lastIndex)
{
traversability_generator3d::TravGenNode *nextNode = curNode->getConnectedNode(curIndex);
if(!nextNode)
{
for(auto *n : curNode->getConnections())
LOG_INFO_S<< "Con Node " << n->getIndex().transpose();;
throw std::runtime_error("Internal error, trajectory is not continuous on tr grid");
}
curNode = nextNode;
lastIndex = curIndex;
}
for(const base::Pose2D &p : cwp.poses)
{
//start is already corrected to be in the middle of a cell, thus cwp.pose.position should not be corrected