Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
multi_robot_router::RouteCoordinatorTimed Class Reference

#include <route_coordinator_timed.h>

Inheritance diagram for multi_robot_router::RouteCoordinatorTimed:
Inheritance graph
[legend]

Classes

class  Timeline
 

Public Member Functions

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 More...
 
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
 checks if a robot can enter a segment at a specific time More...
 
int32_t findPotentialUntilRobotOnSegment (const uint32_t _robot, const uint32_t _segId) const
 returns the time point, when a robot leaves a vertex More...
 
int32_t findSegNr (const uint32_t _robot, const uint32_t _potential) const
 returns the segment id at which the robot is at timepoint _potential More...
 
const uint32_t getEnd (const uint32_t _robotId) const
 returns the Goal of a robot More...
 
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 More...
 
const uint32_t getStart (const uint32_t _robotId) const
 returns the start of a robot More...
 
bool isGoal (const Vertex &_seg, const uint32_t _robotId) const
 returns if a Vertex is the goal vertex for a robot More...
 
void removeRobot (const uint32_t _robot)
 removes a Robot from the Routing Table More...
 
void reset (const std::vector< Segment > &_graph, const uint32_t _nrRobots)
 resets the planning session of multiple robots More...
 
 RouteCoordinatorTimed ()
 constructor More...
 
bool setGoalSegments (const std::vector< uint32_t > &_goalSegments)
 updates the goal segments of the planning attempt More...
 
bool setStartSegments (const std::vector< uint32_t > &_startSegments)
 updates the start segments of the planning attempt More...
 

Private Member Functions

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
 

Private Attributes

std::vector< uint32_t > goalSegments_
 
std::vector< uint32_t > robotSize_
 
std::vector< uint32_t > startSegments_
 
Timeline timeline_
 

Detailed Description

Definition at line 38 of file route_coordinator_timed.h.

Constructor & Destructor Documentation

multi_robot_router::RouteCoordinatorTimed::RouteCoordinatorTimed ( )

constructor

Definition at line 38 of file route_coordinator_timed.cpp.

Member Function Documentation

bool multi_robot_router::RouteCoordinatorTimed::addRoute ( const std::vector< RouteVertex > &  _path,
const uint32_t  _diameterPixel,
const uint32_t  _robotId 
)
virtual

adds a new route to the Routing table and checks if the Routing Table is valid

Parameters
_paththe path to add
_diameterPixelthe diameter of the robot which uses the route
_robotIdthe robotId
Returns
if the new Routing table is valid (if false the new route is not saved in the routing table)

Implements multi_robot_router::RouteCoordinator.

Definition at line 42 of file route_coordinator_timed.cpp.

bool multi_robot_router::RouteCoordinatorTimed::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
virtual

checks if a robot can enter a segment at a specific time

Parameters
_nextthe segment to check
_startTimethe time the current robot enters the segment
_endTimethe time the current robot leaves the segment
_diameterPixelthe diameter of the robot
_collisionRobotreturns the robot wich causes a collision (if no collision -1)
_robotIdthe id of the robot to check
_ignoreGoalif the segment is a goal it is not handled as goal if this param is true. (Used if a robot is pushed away from its goal and has to move back)
Returns
if the vertex is free for the given timespan

Implements multi_robot_router::RouteCoordinator.

Definition at line 112 of file route_coordinator_timed.cpp.

bool multi_robot_router::RouteCoordinatorTimed::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
private

Definition at line 157 of file route_coordinator_timed.cpp.

int32_t multi_robot_router::RouteCoordinatorTimed::findPotentialUntilRobotOnSegment ( const uint32_t  _robot,
const uint32_t  _segId 
) const
virtual

returns the time point, when a robot leaves a vertex

Parameters
_robotthe robotId
_segIdthe segmentId where the time is searched
Returns
the time the robot leaves the segment (-1 means it is a goal Vertex and is occupied forever)

Implements multi_robot_router::RouteCoordinator.

Definition at line 208 of file route_coordinator_timed.cpp.

int32_t multi_robot_router::RouteCoordinatorTimed::findSegNr ( const uint32_t  _robot,
const uint32_t  _potential 
) const
virtual

returns the segment id at which the robot is at timepoint _potential

Parameters
_robotthe robot id
_potentialthe timepoint on the robots path execution
Returns
the segment where the robot is located at time _potential

Implements multi_robot_router::RouteCoordinator.

Definition at line 201 of file route_coordinator_timed.cpp.

const uint32_t multi_robot_router::RouteCoordinatorTimed::getEnd ( const uint32_t  _robotId) const
virtual

returns the Goal of a robot

Implements multi_robot_router::RouteCoordinator.

Definition at line 102 of file route_coordinator_timed.cpp.

std::vector< std::pair< uint32_t, float > > multi_robot_router::RouteCoordinatorTimed::getListOfRobotsHigherPrioritizedRobots ( const uint32_t  _robot,
const uint32_t  _segId,
const int32_t  _potential 
) const
virtual

returns all robots which pass the segment before the given robot and a given time

Parameters
_robotthe robotId
_segIdthe Vertex to check
_potentialthe maximum potential
Returns
all robots which pass the vertex befor _robot and before _potential

Implements multi_robot_router::RouteCoordinator.

Definition at line 213 of file route_coordinator_timed.cpp.

const uint32_t multi_robot_router::RouteCoordinatorTimed::getStart ( const uint32_t  _robotId) const
virtual

returns the start of a robot

Implements multi_robot_router::RouteCoordinator.

Definition at line 107 of file route_coordinator_timed.cpp.

bool multi_robot_router::RouteCoordinatorTimed::isGoal ( const Vertex _seg,
const uint32_t  _robotId 
) const
virtual

returns if a Vertex is the goal vertex for a robot

Parameters
_segthe segment to check
_robotIdthe robot tocheck
Returns
if the vertex is a goal for robot robotId

Implements multi_robot_router::RouteCoordinator.

Definition at line 97 of file route_coordinator_timed.cpp.

void multi_robot_router::RouteCoordinatorTimed::removeRobot ( const uint32_t  _robot)
virtual

removes a Robot from the Routing Table

Parameters
_robotthe robot to remove

Implements multi_robot_router::RouteCoordinator.

Definition at line 218 of file route_coordinator_timed.cpp.

void multi_robot_router::RouteCoordinatorTimed::reset ( const std::vector< Segment > &  _graph,
const uint32_t  _nrRobots 
)
virtual

resets the planning session of multiple robots

Parameters
_graphthe graph
_nrRobotsthe nr of robots to plan

Implements multi_robot_router::RouteCoordinator.

Definition at line 169 of file route_coordinator_timed.cpp.

bool multi_robot_router::RouteCoordinatorTimed::setGoalSegments ( const std::vector< uint32_t > &  _goalSegments)
virtual

updates the goal segments of the planning attempt

Parameters
_goalSegmentsthe goal Segments with length nr_robots
Returns
if the goal segments are valid

Implements multi_robot_router::RouteCoordinator.

Definition at line 177 of file route_coordinator_timed.cpp.

bool multi_robot_router::RouteCoordinatorTimed::setStartSegments ( const std::vector< uint32_t > &  _startSegments)
virtual

updates the start segments of the planning attempt

Parameters
_startSegmentsthe start Segments with length nr_robots
Returns
if the start segments are valid

Implements multi_robot_router::RouteCoordinator.

Definition at line 189 of file route_coordinator_timed.cpp.

Member Data Documentation

std::vector<uint32_t> multi_robot_router::RouteCoordinatorTimed::goalSegments_
private

Definition at line 245 of file route_coordinator_timed.h.

std::vector<uint32_t> multi_robot_router::RouteCoordinatorTimed::robotSize_
private

Definition at line 243 of file route_coordinator_timed.h.

std::vector<uint32_t> multi_robot_router::RouteCoordinatorTimed::startSegments_
private

Definition at line 246 of file route_coordinator_timed.h.

Timeline multi_robot_router::RouteCoordinatorTimed::timeline_
private

Definition at line 244 of file route_coordinator_timed.h.


The documentation for this class was generated from the following files:


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