route_coordinator_timed.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 ROUTE_COORDINATOR_TIMELESS_H
30 #define ROUTE_COORDINATOR_TIMELESS_H
31 
34 
35 namespace multi_robot_router
36 {
37 
39 {
40  class Timeline
41  {
42  typedef struct seg_occupation_t
43  {
44  uint32_t robot;
46  uint32_t startTime;
47  int32_t endTime; //-1 means forever
48  bool mainSeg;
49  seg_occupation_t(const uint32_t _robot, const float &_spaceOcupied, const uint32_t _startTime, const int32_t _endTime) : robot(_robot), spaceOccupied(_spaceOcupied), startTime(_startTime), endTime(_endTime), mainSeg(true)
50  {
51  }
52  seg_occupation_t(const uint32_t _robot, const float &_spaceOcupied, const uint32_t _startTime, const int32_t _endTime, const bool &_mainSeg) : robot(_robot), spaceOccupied(_spaceOcupied), startTime(_startTime), endTime(_endTime), mainSeg(_mainSeg)
53  {
54  }
56 
57  public:
58  Timeline();
59 
65  void reset(const std::vector<Segment> &_graph, const uint32_t _nrRobots);
76  bool addSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, bool _mainSeg);
87  bool checkSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, int32_t &_lastCollisionRobot) const;
98  bool addCrossingSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, const bool &_mainSeg);
109  bool checkCrossingSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, int32_t &_lastCollisionRobot) const;
116  int32_t findSegId(const int32_t _robot, const uint32_t _timestep) const;
121  uint32_t getSize() const;
128  int32_t getTimeUntilRobotOnSegment(const int32_t _robotNr, const uint32_t _segId) const;
136  std::vector<std::pair<uint32_t, float>> getListOfRobotsHigherPrioritizedRobots(const uint32_t _robot, const uint32_t _segId, const int32_t _potential) const;
141  void removeRobot(const uint32_t _robot);
142 
143  private:
144  std::vector<std::vector<seg_occupation>> timeline_;
145  std::vector<std::vector<uint32_t>> robotSegments_;
146  std::vector<float> segmentSpace_;
147  uint32_t maxTime_ = 0;
148  uint32_t nrRobots_ = 0;
149 
150  uint32_t tmpRobot_ = 0;
151  };
152 
153  public:
163  void reset(const std::vector<Segment> &_graph, const uint32_t _nrRobots);
171  bool addRoute(const std::vector<RouteVertex> &_path, const uint32_t _diameterPixel, const uint32_t _robotId);
183  bool checkSegment(const Vertex &_next, const uint32_t _startTime, const int32_t _endTime, const uint32_t _diameterPixel, int32_t &_collisionRobot, const uint32_t _robotId, bool _ignoreGoal = false) const;
189  bool setGoalSegments(const std::vector<uint32_t> &_goalSegments);
195  bool setStartSegments(const std::vector<uint32_t> &_startSegments);
202  bool isGoal(const Vertex &_seg, const uint32_t _robotId) const;
206  const uint32_t getStart(const uint32_t _robotId) const;
210  const uint32_t getEnd(const uint32_t _robotId) const;
217  int32_t findSegNr(const uint32_t _robot, const uint32_t _potential) const;
224  int32_t findPotentialUntilRobotOnSegment(const uint32_t _robot, const uint32_t _segId) const; //-1 means forever
232  std::vector<std::pair<uint32_t, float>> getListOfRobotsHigherPrioritizedRobots(const uint32_t _robot, const uint32_t _segId, const int32_t _potential) const;
237  void removeRobot(const uint32_t _robot);
238 
239  private:
240  // Checks a segment ignoring Crossings
241  bool checkSegmentSingle(const Vertex &_next, const uint32_t _startTime, const int32_t _endTime, const uint32_t _diameterPixel, int32_t &_collisionRobot, const uint32_t _robotId, const bool &_ignoreGoal) const;
242 
243  std::vector<uint32_t> robotSize_;
245  std::vector<uint32_t> goalSegments_;
246  std::vector<uint32_t> startSegments_;
247 };
248 } // namespace multi_robot_router
249 #endif // PATH_COORDINATOR_TIMELESS_H
seg_occupation_t(const uint32_t _robot, const float &_spaceOcupied, const uint32_t _startTime, const int32_t _endTime, const bool &_mainSeg)
void removeRobot(const uint32_t _robot)
removes a Robot from the Routing Table
uint32_t getSize() const
returns the length of the timeline (max Time)
const uint32_t getEnd(const uint32_t _robotId) const
returns the Goal of a robot
bool setStartSegments(const std::vector< uint32_t > &_startSegments)
updates the start segments of the planning attempt
int32_t findSegId(const int32_t _robot, const uint32_t _timestep) const
returns the segment id at which the robot is at timepoint _potential
int32_t findSegNr(const uint32_t _robot, const uint32_t _potential) const
returns the segment id at which the robot is at timepoint _potential
std::vector< std::pair< uint32_t, float > > getListOfRobotsHigherPrioritizedRobots(const uint32_t _robot, const uint32_t _segId, const int32_t _potential) const
returns all robots which pass the segment before the given robot and a given time ...
struct multi_robot_router::RouteCoordinatorTimed::Timeline::seg_occupation_t seg_occupation
bool checkSegmentSingle(const Vertex &_next, const uint32_t _startTime, const int32_t _endTime, const uint32_t _diameterPixel, int32_t &_collisionRobot, const uint32_t _robotId, const bool &_ignoreGoal) const
bool checkCrossingSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, int32_t &_lastCollisionRobot) const
checks if a robot can enter a segment at a specific time if located in a crossing (neighbours > 1) ...
bool checkSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, int32_t &_lastCollisionRobot) const
checks if a robot can enter a segment at a specific time
std::vector< std::vector< uint32_t > > robotSegments_
bool addCrossingSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, const bool &_mainSeg)
adds a segment in a crossing (neighbours > 1) to the timeline and checks if the occupation is valid ...
std::vector< std::vector< seg_occupation > > timeline_
bool isGoal(const Vertex &_seg, const uint32_t _robotId) const
returns if a Vertex is the goal vertex for a robot
int32_t findPotentialUntilRobotOnSegment(const uint32_t _robot, const uint32_t _segId) const
returns the time point, when a robot leaves a vertex
bool addSegment(const uint32_t _startTime, const int32_t _endTime, const uint32_t _segId, const uint32_t _robotNr, const uint32_t _robotSize, bool _mainSeg)
adds a segment to the timeline and checks if the occupation is valid
bool addRoute(const std::vector< RouteVertex > &_path, const uint32_t _diameterPixel, const uint32_t _robotId)
adds a new route to the Routing table and checks if the Routing Table is valid
const uint32_t getStart(const uint32_t _robotId) const
returns the start of a robot
seg_occupation_t(const uint32_t _robot, const float &_spaceOcupied, const uint32_t _startTime, const int32_t _endTime)
int32_t getTimeUntilRobotOnSegment(const int32_t _robotNr, const uint32_t _segId) const
returns the time point, when a robot leaves a vertex
bool setGoalSegments(const std::vector< uint32_t > &_goalSegments)
updates the goal segments of the planning attempt
void reset(const std::vector< Segment > &_graph, const uint32_t _nrRobots)
resets the planning session of multiple robots


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