backtracking_resolution.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, <copyright holder> <email>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY <copyright holder> <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL <copyright holder> <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  */
28 
30 #include <iostream>
31 #define TIMEOVERLAP (1)
32 
33 namespace multi_robot_router
34 {
35 BacktrackingResolution::BacktrackingResolution(uint32_t _timeoverlap) : timeoverlap_(_timeoverlap)
36 {
37 }
38 
40 {
41 }
42 
43 void BacktrackingResolution::resetSession(const RouteCoordinatorWrapper *_route_querry, const PotentialCalculator *_pCalc, const uint32_t _robotDiameter)
44 {
45  route_querry_ = _route_querry;
46  pCalc_ = _pCalc;
47  robotDiameter_ = _robotDiameter;
48  generatedSubgraphs_.clear();
49  encounteredCollisions_.clear();
53 }
54 
55 void BacktrackingResolution::addCollision(const uint32_t robot)
56 {
57  if (encounteredCollisions_.size() <= robot)
58  encounteredCollisions_.resize(robot + 1, 0);
59 
60  encounteredCollisions_[robot]++;
61 }
62 
63 void BacktrackingResolution::saveCollision(const uint32_t _coll)
64 {
65  addCollision(_coll);
66 }
67 
68 const std::vector<uint32_t> &BacktrackingResolution::getRobotCollisions() const
69 {
71 }
72 
73 std::vector<std::reference_wrapper<Vertex>> BacktrackingResolution::resolve(Vertex &_current, Vertex &_next, int32_t _collision)
74 {
75  generatedSubgraphs_.emplace_back();
76  foundSolutions_.clear();
77 
78  //Triggered when a robot blocks a vertex
79  addCollision(_collision);
80 
81  //find the potential when the collision robots leaves the segment
82  float leavePotential = route_querry_->findPotentialUntilRobotOnSegment(_collision, _next.getSegment().getSegmentId());
83 
84  //There is no solution if the colliding robot never leaves the segment.
85  //Therefore, do nothing when leavePotential is smaller zero
86  if (leavePotential >= 0)
87  {
88  trackBack(_current, _next, _collision, leavePotential);
89  }
90 
92  return foundSolutions_;
93 }
94 
95 void BacktrackingResolution::trackBack(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
96 {
97  //Free the next Vertex for new expansion
98  _next.potential = -1;
99  _next.collision = -1;
100 
101  //Return if potential is blocked forever
102  if (_freePotential < 0)
103  return;
104 
105  //If backtracking is not possible (we are on the start vertex) try to wait there
106  //Additionally Backtracking beond wait Segments is not allowed to be able to solve
107  //multi robot scenarios (avoiding n robots in a row)
108  //Anyway backtracking beond wait Segments makes no sense, we will only find allready
109  //found solutions...
110  if (_current.predecessor_ == NULL || _current.isWaitSegment)
111  {
112  int32_t collision = -1;
113 
114  if (route_querry_->checkSegment(_current, 0, _freePotential + 2 * timeoverlap_, robotDiameter_, collision))
115  {
116  _next.potential = -1;
117  _next.collision = -1;
118  //_next.successor_ = NULL; //Tell expander to expand the vertex normally
119 
120  generatedSubgraphs_[resolutionAttemp_].emplace_back(std::make_unique<Vertex>(_current));
121  Vertex &current_n = *(generatedSubgraphs_[resolutionAttemp_].back().get());
122  current_n.potential = _freePotential + 2 * timeoverlap_;
123  current_n.collision = _collision;
124  current_n.successor_ = &_next; //Tell expander to only expand to next
125 
126  foundSolutions_.push_back(current_n);
127  }
128  else
129  {
130  if (_collision != collision)
131  addCollision(collision);
132  }
133  }
134  else //we are somewhere on the path
135  {
136  int32_t collision = -1;
137  bool vertexFree = route_querry_->checkSegment(*_current.predecessor_, _current.predecessor_->potential - timeoverlap_, _freePotential + 2 * timeoverlap_, robotDiameter_, collision);
138 
139  if (vertexFree || collision != -1)
140  {
141  generatedSubgraphs_[resolutionAttemp_].emplace_back(std::make_unique<Vertex>(_current));
142  Vertex &next_n = *(generatedSubgraphs_[resolutionAttemp_].back().get());
143  next_n.potential = -1;
144  next_n.collision = -1;
145 
146  generatedSubgraphs_[resolutionAttemp_].emplace_back(std::make_unique<Vertex>(*(_current.predecessor_)));
147  Vertex &current_n = *(generatedSubgraphs_[resolutionAttemp_].back().get());
148  current_n.potential = _freePotential + 2 * timeoverlap_;
149  current_n.collision = _collision;
150 
151  //Set References
152  current_n.successor_ = &next_n; //Tell expander to only expand to "new next" (with new Potential)
153  next_n.predecessor_ = &current_n;
154  next_n.successor_ = &_next; //Tell expander to only expand to next (we are not allowed to leave the backtracked path)
155 
156  if (vertexFree)
157  {
158  foundSolutions_.push_back(current_n);
159  }
160  else if (collision != -1)
161  {
162  if (collision != -1 && collision != _collision)
163  addCollision(collision);
164 
165  float leavePotential = route_querry_->findPotentialUntilRobotOnSegment(collision, current_n.getSegment().getSegmentId());
166  trackBack(current_n, next_n, collision, leavePotential);
167 
168  //Continue Resolving (Avoid Segment, Avoid Crossing, ...)
169  }
170  }
171  }
172 }
173 } // namespace multi_robot_router
uint32_t getSegmentId() const
Definition: srr_utils.cpp:60
std::vector< std::vector< std::unique_ptr< Vertex > > > generatedSubgraphs_
std::vector< std::reference_wrapper< Vertex > > resolve(Vertex &_current, Vertex &_next, int32_t _collision)
resolves a found collision between two robots.
void trackBack(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
bool checkSegment(const Vertex &_next, const uint32_t _startTime, const int32_t _endTime, const uint32_t _diameterPixel, int32_t &_collisionRobot, bool _ignoreGoal=false) const
calls checkSegment of the routeCoordinator using robot
void resetSession(const RouteCoordinatorWrapper *_route_querry, const PotentialCalculator *_pCalc, const uint32_t _robot_radius)
resets the session (setting the new route querry and potential calculator)
int32_t findPotentialUntilRobotOnSegment(const uint32_t _robot, const uint32_t _segId) const
calls findPotentialUntilRobotOnSegment of the routeCoordinator using robot
void saveCollision(const uint32_t _coll)
increases the collision count of one robot
const std::vector< uint32_t > & getRobotCollisions() const
returns amount of robot collisions found in each resolve try after resetSession
const Segment & getSegment() const
Definition: srr_utils.cpp:88
const RouteCoordinatorWrapper * route_querry_
#define TIMEOVERLAP
std::vector< std::reference_wrapper< Vertex > > foundSolutions_


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:48