srr_utils.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 <ros/ros.h>
31 
32 namespace multi_robot_router
33 {
34 
35 Segment::Segment(const uint32_t &_id, const std::vector<Eigen::Vector2d> &_points, const std::vector<uint32_t> &_successors, const std::vector<uint32_t> &_predecessors, const float &_width) : points_(_points),
36  successors_(_successors),
37  predecessors_(_predecessors)
38 {
39  segmentId_ = _id;
40  width_ = _width;
41  Eigen::Vector2d p = (_points.back() - _points.front());
42  length_ = sqrt(p[0] * p[0] + p[1] * p[1]);
43 }
44 
45 const Eigen::Vector2d &Segment::getEnd() const
46 {
47  return points_.back();
48 }
49 
50 const std::vector<Eigen::Vector2d> &Segment::getPoints() const
51 {
52  return points_;
53 }
54 
55 const std::vector<uint32_t> &Segment::getPredecessors() const
56 {
57  return predecessors_;
58 }
59 
60 uint32_t Segment::getSegmentId() const
61 {
62  return segmentId_;
63 }
64 const Eigen::Vector2d &Segment::getStart() const
65 {
66  return points_.front();
67 }
68 
69 const std::vector<uint32_t> &Segment::getSuccessors() const
70 {
71  return successors_;
72 }
73 
74 float Segment::length() const
75 {
76  return length_;
77 }
78 
79 float Segment::width() const
80 {
81  return width_;
82 }
83 
84 Vertex::Vertex(const Segment &_seg) : predecessors_(), successors_(), segment_(_seg), potential(-1), collision(-1), crossingPredecessor(false), crossingSuccessor(false), isWaitSegment(false)
85 {
86 }
87 
89 {
90  return segment_;
91 }
92 
93 const std::vector<std::reference_wrapper<Vertex>> &Vertex::getPlanningPredecessors() const
94 {
95  return predecessors_;
96 }
97 
98 const std::vector<std::reference_wrapper<Vertex>> &Vertex::getPlanningSuccessors() const
99 {
100  return successors_;
101 }
102 
103 void Vertex::initNeighbours(std::vector<std::unique_ptr<Vertex>> &_sortedVertices, const uint32_t _minSegmentWidth)
104 {
105  for (const uint32_t &vecId : segment_.getPredecessors())
106  {
107  //Use only segments which can be used by any robot
108  if (_sortedVertices[vecId]->getSegment().width() >= _minSegmentWidth)
109  {
110  Vertex &vRef = *(_sortedVertices[vecId].get());
111  predecessors_.push_back(vRef);
112  }
113  }
114 
115  if (predecessors_.size() > 1)
116  {
117  crossingPredecessor = true;
118  }
119 
120  for (const uint32_t &vecId : segment_.getSuccessors())
121  {
122  //Use only segments which can be used by any robot
123  if (_sortedVertices[vecId]->getSegment().width() >= _minSegmentWidth)
124  {
125  Vertex &vRef = *(_sortedVertices[vecId]);
126  successors_.push_back(vRef);
127  }
128  }
129 
130  if (successors_.size() > 1)
131  {
132  crossingSuccessor = true;
133  }
134 }
135 
137 {
138  potential = _v.potential;
139  collision = _v.collision;
140  weight = _v.weight;
141  //direction = _v.direction;
143 }
144 
145 RouteVertex::RouteVertex(const Vertex &_vertex) : segment_(_vertex.getSegment()), direction(path_direction::none), potential(_vertex.potential), collision(_vertex.collision), overlapPredecessor(_vertex.crossingPredecessor), overlapSuccessor(_vertex.crossingSuccessor)
146 {
147 }
148 RouteVertex::RouteVertex(const RouteVertex &_vertex) : segment_(_vertex.getSegment()), direction(_vertex.direction), potential(_vertex.potential), collision(_vertex.collision), overlapPredecessor(_vertex.overlapPredecessor), overlapSuccessor(_vertex.overlapSuccessor)
149 {
150 }
152 {
153  return segment_;
154 }
155 
156 } // namespace multi_robot_router
multi_robot_router::Vertex::crossingPredecessor
bool crossingPredecessor
Definition: srr_utils.h:80
multi_robot_router::Segment::getSuccessors
const std::vector< uint32_t > & getSuccessors() const
Definition: srr_utils.cpp:69
multi_robot_router::Segment::width_
float width_
Definition: srr_utils.h:57
multi_robot_router::Vertex::successors_
std::vector< std::reference_wrapper< Vertex > > successors_
Definition: srr_utils.h:86
multi_robot_router::Segment::successors_
std::vector< uint32_t > successors_
Definition: srr_utils.h:61
ros.h
multi_robot_router::Vertex::getSegment
const Segment & getSegment() const
Definition: srr_utils.cpp:88
multi_robot_router::RouteVertex::RouteVertex
RouteVertex(const Vertex &_vertex)
Definition: srr_utils.cpp:145
multi_robot_router::Vertex::updateVertex
void updateVertex(const Vertex &_v)
Definition: srr_utils.cpp:136
multi_robot_router::Vertex::initNeighbours
void initNeighbours(std::vector< std::unique_ptr< Vertex >> &_sortedVertices, const uint32_t _minSegmentWidth=0)
Definition: srr_utils.cpp:103
multi_robot_router::Segment::getSegmentId
uint32_t getSegmentId() const
Definition: srr_utils.cpp:60
multi_robot_router::Segment::Segment
Segment(const uint32_t &_id, const std::vector< Eigen::Vector2d > &_points, const std::vector< uint32_t > &_successors, const std::vector< uint32_t > &_predecessors, const float &_width)
Definition: srr_utils.cpp:35
multi_robot_router::Segment::getEnd
const Eigen::Vector2d & getEnd() const
Definition: srr_utils.cpp:45
multi_robot_router::Vertex::getPlanningPredecessors
const std::vector< std::reference_wrapper< Vertex > > & getPlanningPredecessors() const
Definition: srr_utils.cpp:93
srr_utils.h
multi_robot_router::Vertex::Vertex
Vertex(const Segment &_seg)
Definition: srr_utils.cpp:84
multi_robot_router::Vertex::getPlanningSuccessors
const std::vector< std::reference_wrapper< Vertex > > & getPlanningSuccessors() const
Definition: srr_utils.cpp:98
multi_robot_router::Segment::getPoints
const std::vector< Eigen::Vector2d > & getPoints() const
Definition: srr_utils.cpp:50
multi_robot_router::Segment::segmentId_
uint32_t segmentId_
Definition: srr_utils.h:56
multi_robot_router::Vertex::predecessor_
Vertex * predecessor_
Definition: srr_utils.h:83
multi_robot_router::Segment::getStart
const Eigen::Vector2d & getStart() const
Definition: srr_utils.cpp:64
multi_robot_router::Vertex::collision
int32_t collision
Definition: srr_utils.h:78
multi_robot_router::Vertex::potential
int32_t potential
Definition: srr_utils.h:77
multi_robot_router::Vertex::crossingSuccessor
bool crossingSuccessor
Definition: srr_utils.h:81
multi_robot_router::RouteVertex::getSegment
const Segment & getSegment() const
Definition: srr_utils.cpp:151
multi_robot_router::Segment::points_
std::vector< Eigen::Vector2d > points_
Definition: srr_utils.h:59
multi_robot_router::Segment::predecessors_
std::vector< uint32_t > predecessors_
Definition: srr_utils.h:60
multi_robot_router::RouteVertex::path_direction
path_direction
Definition: srr_utils.h:95
multi_robot_router::Vertex
Definition: srr_utils.h:65
multi_robot_router::RouteVertex
Definition: srr_utils.h:92
multi_robot_router::Segment::length_
float length_
Definition: srr_utils.h:58
multi_robot_router::Segment
Definition: srr_utils.h:41
multi_robot_router::Segment::getPredecessors
const std::vector< uint32_t > & getPredecessors() const
Definition: srr_utils.cpp:55
multi_robot_router::Segment::width
float width() const
Definition: srr_utils.cpp:79
multi_robot_router::Vertex::weight
int32_t weight
Definition: srr_utils.h:79
multi_robot_router::Vertex::segment_
const Segment & segment_
Definition: srr_utils.h:88
multi_robot_router::RouteVertex::segment_
const Segment & segment_
Definition: srr_utils.h:110
multi_robot_router
Definition: avoidance_resolution.h:37
multi_robot_router::Vertex::predecessors_
std::vector< std::reference_wrapper< Vertex > > predecessors_
Definition: srr_utils.h:87
multi_robot_router::Segment::length
float length() const
Definition: srr_utils.cpp:74


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:10:16