single_robot_router.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 
32 
33 namespace multi_robot_router
34 {
35 SingleRobotRouter::SingleRobotRouter() : segment_expander_(SegmentExpander::CollisionResolverType::avoidance)
36 {
37 }
38 
40 {
41 }
42 
44 {
46 }
47 
49 {
51 }
52 
53 bool SingleRobotRouter::getRouteCandidate(const uint32_t _start, const uint32_t _goal, const RouteCoordinatorWrapper &path_coordinator, const uint32_t _robotDiameter, const float &_robotSpeed, std::vector<RouteVertex> &_path, const uint32_t _maxIterations)
54 {
55  robotDiameter_ = _robotDiameter;
56  resetAttempt();
57  segment_expander_.setSpeed(_robotSpeed);
58 
59  if (!segment_expander_.calculatePotentials(&path_coordinator, *(searchGraph_[_start].get()), *(searchGraph_[_goal].get()), _maxIterations, robotDiameter_))
60  {
61  lastAttempt_ = false;
62  return false;
63  }
64 
65  std::vector<RouteVertex> reversedPath;
66 
67  if (!traceback_.getPath(*(searchGraph_[_start].get()), *(searchGraph_[_goal].get()), reversedPath))
68  {
69  lastAttempt_ = false;
70  return false;
71  }
72 
73  _path.clear();
74 
75  for (std::vector<RouteVertex>::const_iterator rit = reversedPath.cend(); rit != reversedPath.cbegin();)
76  {
77  rit--;
78  _path.emplace_back(*rit);
79  }
80 
81  lastAttempt_ = true;
82  return true;
83 }
84 
86 {
88 
89  for (std::unique_ptr<Vertex> &v : searchGraph_)
90  {
91  v->potential = -1;
92  v->collision = -1;
93  v->weight = 0;
94  v->predecessor_ = NULL;
95  }
96 }
97 
99 {
100  return lastAttempt_;
101 }
102 
103 void SingleRobotRouter::initSearchGraph(const std::vector<Segment> &_graph, const uint32_t minSegmentWidth_)
104 {
105  searchGraph_.clear();
106 
107  for (const Segment &seg : _graph)
108  {
109  searchGraph_.push_back(std::make_unique<Vertex>(seg));
110  }
111 
112  for (std::unique_ptr<Vertex> &v : searchGraph_)
113  {
114  v->initNeighbours(searchGraph_, minSegmentWidth_);
115  }
116 }
117 
118 const std::vector<uint32_t> &SingleRobotRouter::getRobotCollisions() const
119 {
121 }
122 } // namespace multi_robot_router
CollisionResolverType getCollisionResolver() const
gets the currently used collision resolver
bool getRouteCandidate(const uint32_t _start, const uint32_t _goal, const RouteCoordinatorWrapper &path_coordinator, const uint32_t _robotDiameter, const float &_robotSpeed, std::vector< RouteVertex > &path, const uint32_t _maxIterations)
calculates a route candidate coordinated with other robots by the given route Coordinated ...
virtual bool getPath(const Vertex &_startSeg, const Vertex &_endSeg, std::vector< RouteVertex > &_path) const
traces back the graph to find the shortest route of the graph
Definition: traceback.cpp:35
bool getLastResult()
returns the result of the last planning attempt
std::vector< std::unique_ptr< Vertex > > searchGraph_
void initSearchGraph(const std::vector< Segment > &_graph, const uint32_t minSegmentWidth_=0)
generates the search graph out of the given graph (and optimizes it)
void setCollisionResolver(const CollisionResolverType cRes)
sets the desired collision resolver
const std::vector< uint32_t > & getRobotCollisions() const
returns the found robot collisions while planning
void setSpeed(const float &_speed)
Sets the multiplier to reduce a robots speed (pCalc...)
void setCollisionResolver(const SegmentExpander::CollisionResolverType cRes)
sets the collisionResolver used
bool calculatePotentials(const RouteCoordinatorWrapper *_p, Vertex &_start, Vertex &_end, const uint32_t _maxIterations, const uint32_t _radius)
assigns all Vertices in the Search graph with a potential according to the distance to the start ...
SegmentExpander::CollisionResolverType getCollisionResolverType() const
returns the CollisionResolverType
const std::vector< uint32_t > & getRobotCollisions() const
returns the found robotCollisions while planning


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Mon Feb 28 2022 23:57:49