Go to the documentation of this file.
29 #ifndef ROUTE_COORDINATOR_H
30 #define ROUTE_COORDINATOR_H
47 virtual void reset(
const std::vector<Segment> &_graph,
const uint32_t _nrRobots) = 0;
59 virtual bool addRoute(
const std::vector<RouteVertex> &_path,
const uint32_t _diameterPixel,
const uint32_t _robotId) = 0;
65 virtual 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 = 0;
71 virtual bool setGoalSegments(
const std::vector<uint32_t> &_goalSegments) = 0;
77 virtual bool setStartSegments(
const std::vector<uint32_t> &_startSegments) = 0;
84 virtual bool isGoal(
const Vertex &_seg,
const uint32_t _robotId)
const = 0;
88 virtual const uint32_t
getStart(
const uint32_t _robotId)
const = 0;
92 virtual const uint32_t
getEnd(
const uint32_t _robotId)
const = 0;
105 virtual void removeRobot(
const uint32_t _robot) = 0;
112 virtual int32_t
findSegNr(
const uint32_t _robot,
const uint32_t _potential)
const = 0;
133 bool checkSegment(
const Vertex &_next,
const uint32_t _startTime,
const int32_t _endTime,
const uint32_t _diameterPixel, int32_t &_collisionRobot,
bool _ignoreGoal =
false)
const;
145 const uint32_t
getEnd()
const;
153 int32_t
findSegNr(
const uint32_t _robot,
const uint32_t _potential)
const;
164 #endif // PATH_QUERRY_H
virtual const uint32_t getEnd(const uint32_t _robotId) const =0
returns the Goal of a robot
virtual int32_t findPotentialUntilRobotOnSegment(const uint32_t _robot, const uint32_t _segId) const =0
returns the time point, when a robot leaves a vertex
virtual const uint32_t getStart(const uint32_t _robotId) const =0
returns the start of a robot
int32_t findSegNr(const uint32_t _robot, const uint32_t _potential) const
calls findSegNr of the routeCoordinator using robot
const RouteCoordinator * routeCoordinator_
virtual int32_t findSegNr(const uint32_t _robot, const uint32_t _potential) const =0
returns the segment id at which the robot is at timepoint _potential
const uint32_t getStart() const
calls getStart of the routeCoordinator using robot
virtual void removeRobot(const uint32_t _robot)=0
removes a Robot from the Routing Table
virtual std::vector< std::pair< uint32_t, float > > getListOfRobotsHigherPrioritizedRobots(const uint32_t _robot, const uint32_t _segId, const int32_t _potential) const =0
returns all robots which pass the segment before the given robot and a given time
virtual 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 =0
updates the goal segments of the planning attempt
bool isGoal(const Vertex &_seg) const
calls isGoal of the routeCoordinator using robot
const uint32_t getEnd() const
calls getEnd of the routeCoordinator using robot
int32_t findPotentialUntilRobotOnSegment(const uint32_t _robot, const uint32_t _segId) const
calls findPotentialUntilRobotOnSegment of the routeCoordinator using robot
virtual void reset(const std::vector< Segment > &_graph, const uint32_t _nrRobots)=0
resets the planning session of multiple robots
virtual bool isGoal(const Vertex &_seg, const uint32_t _robotId) const =0
returns if a Vertex is the goal vertex for a robot
virtual bool setGoalSegments(const std::vector< uint32_t > &_goalSegments)=0
updates the goal segments of the planning attempt
virtual bool addRoute(const std::vector< RouteVertex > &_path, const uint32_t _diameterPixel, const uint32_t _robotId)=0
checks if a robot can enter a segment at a specific time
RouteCoordinatorWrapper(const uint32_t _robot, const RouteCoordinator &_routeCoordinater)
constructor to save the routecoordinator and the current robot
std::vector< std::pair< uint32_t, float > > getListOfRobotsHigherPrioritizedRobots(const uint32_t _robot, const uint32_t _segId, const int32_t _potential) const
calls getListOfRobotsHigherPrioritizedRobots of the routeCoordinator using robot
virtual bool setStartSegments(const std::vector< uint32_t > &_startSegments)=0
updates the start segments of the planning attempt
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