Class Graph
Defined in File Graph.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Graph
Public Functions
-
Graph()
Default constructor.
-
Waypoint &add_waypoint(std::string map_name, Eigen::Vector2d location)
Make a new waypoint for this graph. It will not be connected to any other waypoints until you use make_lane() to connect it.
Note
Waypoints cannot be erased from a Graph after they are created.
-
const Waypoint &get_waypoint(std::size_t index) const
const-qualified get_waypoint()
-
Waypoint *find_waypoint(const std::string &key)
Find a waypoint given a key name. If the graph does not have a matching key name, then a nullptr will be returned.
-
const Waypoint *find_waypoint(const std::string &key) const
const-qualified find_waypoint()
-
bool add_key(const std::string &key, std::size_t wp_index)
Add a new waypoint key name to the graph. If a new key name is given, then this function will return true. If the given key name was already in use, then this will return false and nothing will be changed in the graph.
-
bool remove_key(const std::string &key)
Remove the waypoint key with the given name, if it exists in this Graph. If the key was removed, this will return true. If the key did not exist, this will return false.
-
bool set_key(const std::string &key, std::size_t wp_index)
Set a waypoint key. If this key is already in the Graph, it will be changed to the new association.
This function will return false if wp_index is outside the range of the waypoints in this Graph.
-
const std::unordered_map<std::string, std::size_t> &keys() const
Get the map of all keys in this Graph.
-
Lane &add_lane(const Lane::Node &entry, const Lane::Node &exit, Lane::Properties properties = Lane::Properties())
Make a lane for this graph. Lanes connect waypoints together, allowing the graph to know how the robot is allowed to traverse between waypoints.
-
const Lane &get_lane(std::size_t index) const
const-qualified get_lane()
-
const std::vector<std::size_t> &lanes_from(std::size_t wp_index) const
Get the indices of lanes that come out of the given Waypoint index.
-
const std::vector<std::size_t> &lanes_into(std::size_t wp_index) const
Get the indices of lanes that arrive into the given Waypoint index.
-
Lane *lane_from(std::size_t from_wp, std::size_t to_wp)
Get a reference to the lane that goes from from_wp to to_wp if such a lane exists. If no such lane exists, this will return a nullptr. If multiple exist, this will return the one that was added most recently.
-
const Lane *lane_from(std::size_t from_wp, std::size_t to_wp) const
const-qualified lane_from()
-
class Lane
Add a lane to connect two waypoints.
Public Functions
-
Node &entry()
Get the entry node of this Lane. The lane represents an edge in the graph that goes away from this node.
-
Node &exit()
Get the exit node of this Lane. The lane represents an edge in the graph that goes into this node.
-
Properties &properties()
Get the properties of this Lane.
-
const Properties &properties() const
const-qualified properties()
-
class Dock
-
class Door
A door in the graph which needs to be opened before a robot can enter a certain lane or closed before the robot can exit the lane.
Subclassed by rmf_traffic::agv::Graph::Lane::DoorClose, rmf_traffic::agv::Graph::Lane::DoorOpen
-
class Event
An abstraction for the different kinds of Lane events.
Public Functions
-
template<typename DerivedExecutor>
inline DerivedExecutor &execute(DerivedExecutor &executor) const
-
virtual ~Event() = default
Public Static Functions
-
static EventPtr make(LiftSessionBegin open)
-
static EventPtr make(LiftSessionEnd close)
-
static EventPtr make(LiftDoorOpen open)
-
template<typename DerivedExecutor>
-
class Executor
A customizable Executor that can carry out actions based on which Event type is present.
Public Types
-
using LiftSessionBegin = Lane::LiftSessionBegin
-
using LiftDoorOpen = Lane::LiftDoorOpen
-
using LiftSessionEnd = Lane::LiftSessionEnd
Public Functions
-
virtual void execute(const LiftSessionBegin &begin) = 0
-
virtual void execute(const LiftDoorOpen &open) = 0
-
virtual void execute(const LiftSessionEnd &end) = 0
-
virtual ~Executor() = default
-
using LiftSessionBegin = Lane::LiftSessionBegin
-
class LiftDoorOpen : public rmf_traffic::agv::Graph::Lane::LiftSession
Public Functions
-
class LiftMove : public rmf_traffic::agv::Graph::Lane::LiftSession
Public Functions
-
class LiftSession
A lift door in the graph which needs to be opened before a robot can enter a certain lane or closed before the robot can exit the lane.
Subclassed by rmf_traffic::agv::Graph::Lane::LiftDoorOpen, rmf_traffic::agv::Graph::Lane::LiftMove, rmf_traffic::agv::Graph::Lane::LiftSessionBegin, rmf_traffic::agv::Graph::Lane::LiftSessionEnd
Public Functions
-
LiftSession(std::string lift_name, std::string floor_name, Duration duration)
Constructor
- Parameters:
lift_name – [in] Name of the lift that this door belongs to.
floor_name – [in] Name of the floor that this door belongs to.
duration – [in] How long the door takes to open or close.
-
const std::string &lift_name() const
Get the name of the lift that the door belongs to.
-
LiftSession &lift_name(std::string name)
Set the name of the lift that the door belongs to.
-
const std::string &floor_name() const
Get the name of the floor that this door is on.
-
LiftSession &floor_name(std::string name)
Set the name of the floor that this door is on.
-
LiftSession &duration(Duration duration)
Set an estimate of how long it will take the door to open or close.
-
LiftSession(std::string lift_name, std::string floor_name, Duration duration)
-
class LiftSessionBegin : public rmf_traffic::agv::Graph::Lane::LiftSession
Public Functions
-
class LiftSessionEnd : public rmf_traffic::agv::Graph::Lane::LiftSession
Public Functions
-
class Node
A Lane Node wraps up a Waypoint with constraints. The constraints stipulate the conditions for entering or exiting the lane to reach this waypoint.
Public Functions
-
Node(std::size_t waypoint_index, rmf_utils::clone_ptr<Event> event = nullptr, rmf_utils::clone_ptr<OrientationConstraint> orientation = nullptr)
Constructor
- Parameters:
waypoint_index – The index of the waypoint for this Node
event – An event that must happen before/after this Node is approached (before if it’s an entry Node or after if it’s an exit Node).
orientation – Any orientation constraints for moving to/from this Node (depending on whether it’s an entry Node or an exit Node).
-
Node(std::size_t waypoint_index, rmf_utils::clone_ptr<OrientationConstraint> orientation)
Constructor. The event parameter will be nullptr.
-
const Event *event() const
Get a reference to an event that must occur before or after this Node is visited.
Note
Before if this is an entry node or after if this is an exit node
-
Node &event(rmf_utils::clone_ptr<Event> new_event)
Set the event that must occur before or after this Node is visited.
-
const OrientationConstraint *orientation_constraint() const
Get the constraint on orientation that is tied to this Node.
-
Node(std::size_t waypoint_index, rmf_utils::clone_ptr<Event> event = nullptr, rmf_utils::clone_ptr<OrientationConstraint> orientation = nullptr)
-
class Properties
The Lane Properties class contains properties that apply across the full extent of the lane.
Public Functions
-
Properties()
Construct a default set of properties
speed_limit: nullopt
-
std::optional<double> speed_limit() const
Get the speed limit along this lane. If a std::nullopt is returned, then there is no specified speed limit for the lane.
-
Properties &speed_limit(std::optional<double> value)
Set the speed limit along this lane. Providing a std::nullopt indicates that there is no speed limit for the lane.
-
Properties()
-
class Wait
-
Node &entry()
-
class OrientationConstraint
A class that implicitly specifies a constraint on the robot’s orientation.
Public Functions
-
virtual bool apply(Eigen::Vector3d &position, const Eigen::Vector2d &course_vector) const = 0
Apply the constraint to the given homogeneous position.
- Parameters:
position – [inout] The position which needs to be constrained. The function should modify this position such that it satisfies the constraint, if possible.
course_vector – [in] The direction that the robot is travelling in. Given for informational purposes.
- Returns:
True if the constraint is satisfied with the new value of position. False if the constraint could not be satisfied.
-
virtual rmf_utils::clone_ptr<OrientationConstraint> clone() const = 0
Clone this OrientationConstraint.
-
virtual ~OrientationConstraint() = default
Public Static Functions
-
static rmf_utils::clone_ptr<OrientationConstraint> make(std::vector<double> acceptable_orientations)
Make an orientation constraint that requires a specific value for the orientation.
-
static rmf_utils::clone_ptr<OrientationConstraint> make(Direction direction, const Eigen::Vector2d &forward_vector)
Make an orientation constraint that requires the vehicle to face forward or backward.
-
virtual bool apply(Eigen::Vector3d &position, const Eigen::Vector2d &course_vector) const = 0
-
class Waypoint
Public Functions
-
bool is_holding_point() const
Returns true if this Waypoint can be used as a holding point for the vehicle, otherwise returns false.
-
Waypoint &set_holding_point(bool _is_holding_point)
Set whether this waypoint can be used as a holding point for the vehicle.
-
bool is_passthrough_point() const
Returns true if this Waypoint is a passthrough point, meaning a planner should not have a robot wait at this point, even just briefly to allow another robot to pass. Setting passthrough points reduces the branching factor of a planner, allowing it to run faster, at the cost of losing possible solutions to conflicts.
-
bool is_parking_spot() const
Returns true if this Waypoint is a parking spot. Parking spots are used when an emergency alarm goes off, and the robot is required to park itself.
-
bool is_charger() const
Returns true if this Waypoint is a charger spot. Robots are routed to these spots when their batteries charge levels drop below the threshold value.
-
std::size_t index() const
The index of this waypoint within the Graph. This cannot be changed after the waypoint is created.
-
const std::string *name() const
If this waypoint has a name, return a reference to it. If this waypoint does not have a name, return a nullptr.
The name of a waypoint can only be set using add_key() or set_key().
-
std::string name_or_index(const std::string &name_format = "%s", const std::string &index_format = "#%d") const
If this waypoint has a name, the name will be returned. Otherwise it will return the waypoint index, formatted into a string based on the index_format argument.
- Parameters:
name_format – [in] If this waypoint has an assigned name, the first instance of “%s” within name_format will be replaced with the name of the waypoint. If there is no s in the name_format string, then this function will simply return the name_format string as-is when the waypoint has a name.
index_format – [in] If this waypoint does not have an assigned name, the first instance of “%d” within the index_format string will be replaced with the stringified decimal index value of the waypoint. If there is no “%d” in the index_format string, then this function will simply return the index_format string as-is when the waypoint does not have a name.
-
bool is_holding_point() const
-
Graph()