avoidance_resolution.h
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 
29 #ifndef AVOIDANCE_RESOLUTION_H
30 #define AVOIDANCE_RESOLUTION_H
31 
35 #include <queue>
36 
38 {
40 {
41  public:
46  AvoidanceResolution(uint32_t _timeoverlap);
48 
55  void resetSession(const RouteCoordinatorWrapper *_route_querry, const PotentialCalculator *_pCalc, const uint32_t _robot_radius);
63  std::vector<std::reference_wrapper<Vertex>> resolve(Vertex &_current, Vertex &_next, int32_t _collision);
68  const std::vector<uint32_t> &getRobotCollisions() const;
73  void saveCollision(const uint32_t _coll);
74 
75  private:
76  struct queueElement
77  {
80  int32_t collision;
81  float potential;
82  };
83 
84  //Tracks back until a free vertex or the start vertex is found to avoid a robot
85  void trackBack(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
86  //Tries to avoid a robot on a free segment of a crossing, which is not part of the route
87  void avoid(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
88  //Expands to the next segment and back to the current one
89  void moveSegment(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
90  //Expands to the next segment and back to the current one
91  bool expandSegment(const Vertex &cSeg, Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
92  //Avoids a robot by inserting a wait Vertex before start
93  void avoidStart(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
94  //Avoids a robot by inserting a wait Vertex after goal
95  void avoidGoal(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential);
96  //Saves robot collisions automatically extending the collision vertex
97  void addCollision(const uint32_t robot);
98 
101  uint32_t timeoverlap_;
102  uint32_t robotDiameter_;
103  //unique_ptr to keep references of Vertex (Heap), because the list is updated while runtime
104  std::vector<std::vector<std::unique_ptr<Vertex>>> generatedSubgraphs_;
105  std::vector<std::reference_wrapper<Vertex>> foundSolutions_;
106  std::vector<uint32_t> encounteredCollisions_;
107  uint32_t resolutionAttemp_ = 0;
110  std::queue<queueElement> queue_;
111 };
112 } // namespace multi_robot_router
113 #endif // HEURISTIC_H
const std::vector< uint32_t > & getRobotCollisions() const
returns amount of robot collisions found in each resolve try after resetSession
std::vector< std::reference_wrapper< Vertex > > foundSolutions_
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)
void avoidStart(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
const RouteCoordinatorWrapper * route_querry_
void saveCollision(const uint32_t _coll)
increases the collision count of one robot
void avoidGoal(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
bool expandSegment(const Vertex &cSeg, Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
void moveSegment(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
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 avoid(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)
void trackBack(Vertex &_current, Vertex &_next, const int32_t _collision, const float _freePotential)


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