maliput
|
This document describes maliput
, a model of road networks for use in agent and traffic simulations. At the core of maliput
is a mathematical model of the geometry and topology of a road network. That model is practically expressed by an abstract C++ API which is intended to be independent of any specific on-disk format for persistent road data. Concrete implementations of the abstract API allow various sources of road network data to be expressed via the common maliput
model.
Driving happens on roads (most of the time); the road network is a fundamental structure in the task of driving. Any non-trivial simulation of driving will involve some model of roads — the surface on which the vehicles are moving. Our top-level goals for the maliput
model are:
(1): The ado are the supporting actors in Kyogen, a form of Japanese comic theater traditionally performed in the interludes between Noh plays, featuring farcical depictions of daily life.
For both of these goals, we need to know where vehicles and other objects are (and where they are going) with respect to one another in the context of the road. Thus, the maliput
API provides methods to answer questions such as "How close am I to the edge of the lane?" and "What objects are within 100 meters ahead of me in my current lane?"
maliput
is intended to be agnostic of the data source for a road network. Concrete implementations for different data sources will expose the same abstract interface. Some networks may be completely synthetic (constructed by hand, or even procedurally), others will be created from measurements of real-life roads.
We expect to have implementations to support:
The C++ API is also intended to allow for tiling, i.e., instantiating fragments of very large, complex road networks on-demand and disposing of fragments that are no longer immediately necessary.
At the core of maliput
is a mathematical model for the geometry of the space around a road network; it is a model of both the road surface and the volume proximal to that surface. In the abstract, one can think of "a road" as a 2D manifold (the road surface) embedded in 3D space (the physical universe). The manifold structure is important because much of driving involves figuring out where things are in relation to the road. The embedding is important, too, because physical sensing and actuation (and realistic visualization) happens in physical space. In maliput
, we consider the road volume and not just the road surface because we want to be able to describe objects and events which are not glued to the surface — e.g., stop lights, street signs, watermelons falling off of trucks.
In super-mathy terms:
Inertial
-frame*.Inertial
-frame via a \( G^1 \) continuous map from \( \mathbb{R}^2 \to \mathbb{R}^3 \).Inertial
-frame via a \( G^1 \) continuous map from \( \mathbb{R}^3 \to \mathbb{R}^3 \).In the lexicon of maliput
and its C++ API, the road volume manifold is called a RoadGeometry
. A RoadGeometry
is partitioned into Segments
, which correspond to stretches of asphalt (and the space above and/or below them). Each Segment
is a group of one or more adjacent Lanes
. A Lane
corresponds to a lane of travel on a road, and defines a specific parameterization of the parent Segment
's volume from a local lane frame into the Inertial
-frame. Lanes
are connected at BranchPoints
, and the graph of Lanes
and BranchPoints
describes the topology of a RoadGeometry
. Segments
which map to intersecting volumes of the Inertial
-frame (e.g., intersections) are grouped together into Junctions
.
In a sense, there are two complementary object graphs in maliput
. The container hierarchy (Junctions
contain Segments
, which contain Lanes
) groups together different views of the same regions of road surface. The routing graph (Lanes
are joined end-to-end via BranchPoints
) describes how one can get from one region of the road network to another.
A RoadGeometry
may also model paths that are adjacent to roads like sidewalks. If there is no \( G^1 \) continuity between the road and its adjacent paths, the two must be separated by Segment
boundaries. This is not in violation of Maliput's continuity requirements because Maliput has no notion of laterally-adjacent Segments
.
TODO: Explain the concepts of linear tolerance, angular tolerance, and characteristic scale length.
Two types of coordinate frames are used in this model: the (single) Inertial
-frame and the (multiple) Lane
-frames. In both, distances are typically measured in units of meters.
The Inertial
-frame is any right-handed 3D inertial Cartesian coordinate system, with orthonormal basis \((\hat{x},\hat{y},\hat{z})\) and positions expressed as triples \((x,y,z)\). This could be a globally-flat coordinate system, e.g., ECEF ("Earth-centered,
Earth-fixed"). Or, it could be a locally-flat projection of the Earth's surface, e.g., a UTM ("Universal Transverse Mercator") projection coupled with elevation. No specific projection is mandated by maliput
. To disambiguate for one or another Inertial
-frame choice, the API uses the preferred InertialPosition
type which can be interpreted for one or another frame choice.
Currently: \(\hat{z}\) is assumed to be up, with \(z\) representing an altitude or elevation. \(\hat{x}\) and \(\hat{y}\) span the horizontal plane. Typically, the "ENU" convention is used: \(\hat{x}\) points East and \(\hat{y}\) points North.
Another frame will be defined, the Backend
-frame which is different from the Inertial
-frame by an isometric transform. This frame is also a right-handed 3D inertial Cartesian coordinate system with an orthonormal basis. It exists and potentially differs from the Inertial
-frame because of differing contexts. Typically, the Inertial
-frame chosen matches that of the client, e.g., a simulator that uses Maliput. Meanwhile, the Backend
-frame typically matches the underlying data used by a particular backend, e.g., an OpenDRIVE file. The Backend
-frame will use Vector3
for coordinates to properly differentiate from the Inertial
-frame type, i.e. InertialPosition
.
A Lane
-frame is a right-handed orthonormal curvilinear coordinate system, with positions expressed as coordinates \((s,r,h)\). Each Lane
in a RoadGeometry
defines its own embedding into the Inertial
space, and thus each Lane
has its own Lane
-frame.
When embedded into the Inertial
space, \(s\) represents longitudinal distance (path-length) along a central reference curve (the centerline) which defines a given Lane
. \(r\) is lateral distance along the road surface, the path length along a geodesic perpendicular to the centerline. \(h\) is height above the road surface, the distance along a normal. Unless the lane is completely straight and flat, a Lane
-frame acts like a non-inertial system: the \((s,r,h)\) are not isotropic ( \(s\) is only guaranteed to correspond to true physical distance when \((r,h) = (0,0)\) (i.e., along the centerline), and similarly \(r\) only yields a true physical distance when \(h = 0\) (i.e., along the road surface).) and the curves and twists in the embedding introduce fictitious forces in equations of motion expressed in these coordinates.
TODO: see discussion in https://github.com/ToyotaResearchInstitute/maliput_malidrive/issues/16 For certain roads whose lateral profile is a straight line, geodetic curves would likely be straight lines. However, that's not true for the general case and the \(r\) distance is not trivially computed. Most backend implementations might choose to approximate the arc length of the geodetic curve by a path length of a straight line measured in the
Inertial
space.
TODO: Replace this gibberish with a proper description of the effects of the metric induced by the push forward of \(W_L\). We also introduce the notion of /isotropic coordinates/ \((\sigma,\rho,\eta)\) corresponding to the non-isotropic \((s,r,h)\). At every point \((s,r,h)\) in a
Lane
with its local \((\hat{s},\hat{r},\hat{h})\) coordinate frame, we define a corresponding \((\hat{\sigma},\hat{\rho},\hat{\eta})\) frame with the same orientation but different scale factors which make it isotropic. We don't use \((\sigma,\rho,\eta)\) to parameterize the space of theLane
, but rather to talk about physically-relevant velocities and accelerations. In other words, at a given point in aLane
, the magnitude of a velocity \((\dot{\sigma},\dot{\rho},\dot{\eta})\) is unchanged when mapped to \((\dot{x},\dot{y},\dot{z})\), and the direction undergoes the same rotation for all velocity vectors anchored to that point.
Finally, we will colloquially use the term "`Road`-frame" to refer to a 4-tuple of parameters \((L,s,r,h)\) in which:
Lane
;Lane
-frame coordinates understood in the context of Lane
\(L\).One can construct a map \(W: \lbrace(L,s,r,h)\rbrace \to \mathbb{R}^3\) from the road manifold into the Inertial
space, as a union of the per Lane
maps. This \(W\) is technically an immersion and not an embedding because it is not necessarily 1-to-1; as described later on, multiple Lanes
in the same Segment
will double-cover the same region of the \(\mathbb{R}^3\) Inertial
-frame. Also, due to our representation of routing, double-coverage will occur where streets cross to form intersections, or where highways split or merge. This needs to be considered when determining the possible interactions of agents or objects that are located in nominally distinct regions of the Lane
network.
Note: Due to certain geometric constraints in
Lane
-frame parameterization, some regions of theRoadGeometry
manifold may not be covered by theLane
-frame of anyLane
. We anticipate needing an additional set of surface/volume parameterizations in the future to complete the picture.
A Lane
represents a lane of travel in a road network, expressing a path along a stretch of asphalt as well as a parameterization of that asphalt from one lateral edge to the other (including adjacent lanes of travel, shoulders, etc).
As discussed above, a Lane
, identified by \(L\), defines a map \(W_L\) from curvilinear coordinates to the Inertial
-frame:
\[ W_L: (s,r,h) \mapsto (x,y,z), \text{ for } s \in [0, s_\text{max}] \]
The curve traced out by \(W_L\) along longitudinal coordinate \(s\) (while \(r\) and \(h\) are fixed to zero) is called the centerline of the Lane
:
\[ C_L: s \mapsto (x,y,z), = W_L(s,0,0) \text{ for } s \in [0, s_\text{max}] \]
The centerline is nominally the ideal trajectory of a vehicle traveling in the lane (and it is not necessarily in the geometric center of the lane, despite the name). \(W_L\) is required to be \(C^1\) continuous, and thus \(C_L\) is also required to be \(C^1\) continuous.
The space of the Lane
is bounded in \(s\) by \(s \in [0, s_\text{max}]\). \(s_\text{max}\) is called the length of the Lane
and is in fact the path-length of the centerline \(C_L\) (in both the Lane
-frame and the Inertial
-frame). The \(s=0\) end of a Lane
is labeled the start end, and the \(s=s_\text{max}\) end is the finish end. However, a Lane
is just a stretch of pavement with no preferred travel direction, and there is no direction of travel implied by these labels. (2)
(2): Travel restrictions on a Lane
are indicated by road rule annotations, described later in section
A Lane
is bounded laterally by segment bounds, \(r \in B_\text{segment}(s)\), where
\[ B_\text{segment}: s \mapsto [r_\text{min}, r_\text{max}] \text{ s.t. } r_\text{min}<=0 \text{ and } r_\text{max}>=0 \]
defines inclusive min/max bounds which depend only on \(s\). These are the \(segment bounds\) for the Lane
, the valid domain of \(r\), which is intended to represent the full lateral extent of the Segment
including all adjacent Lanes
.
TODO: This begs for a picture.
A Lane
is also characterized by nominal bounds, \(r \in B_\text{nominal}(s)\), where
\[ B_\text{nominal}: s \mapsto [r_\text{min}, r_\text{max}] \text{ s.t. } B_\text{nominal} \subseteq B_\text{segment} \]
which indicate what is considered to be "in" that specific travel lane (e.g., between the stripes).
A Lane
is bounded in height by \(h \in H_\text{lane}(s,r)\), where
\[ H_\text{lane}: (s,r) \mapsto [h_\text{min}, h_\text{max}] \text{ s.t. } h_\text{min}<=0 \text{ and } h_\text{max}>=0 \]
defines inclusive min/max bounds which depend on \(s\) and \(r\). These define the valid domain of \(h\), which represents the full extent of the volume (above and possibly below the road surface) modeled by the Lane
. Typically, \(h_\text{min}\) is zero, but having \(h_\text{min}<0\) allows a Lane
to describe the location of subterranean features (e.g., measurements made by ground-penetrating radar).
Note: Because of the orthogonality of the \((s,r,h)\) coordinates, a curve with constant non-zero \((r,h)\) (imagine \(r\) and \(h\) "grid lines") is basically a parallel curve to the centerline \(C_L\). Thus, the shape of \(C_L\) and/or the road surface may produce limits to \((r,h)\) before such a curve develops a cusp. The current definitions of \(B_\text{segment}\) and \(H_\text{lane}\) conflate the bounds of the /segment/ volume (e.g., pavement and free space under bridges) with the bounds of the /modeled/ volume (e.g., the bounds on \(r\) and \(h\) which maintain \(G^1\) continuity, avoiding cusps). Hence, the road surface may continue into regions that cannot be properly represented by the parameterization of a given
Lane
.
BranchPoints
are the points where Lanes
are connected end-to-end. They are so named because they are the branch-points in the decision tree of an agent driving in the network, which must decide which new Lane
to follow at the end of its current Lane
. Each end (start or finish) of a Lane
has an associated BranchPoint
(3). Each BranchPoint
has at least one Lane
associated with it, typically two, and often more than that (when Lanes
merge/diverge). (4)
We only allow BranchPoints
to occur at the ends of Lanes
, specifically at the ends of their centerlines ( \(C_L(s)\)). We also require that the centerlines of the Lanes
joined at a BranchPoint
are \(G^1\) continuous. Together with the earlier-stated requirement of overall \(G^1\) continuity of the road surface and the conditions on \(r\) and \(h\) being path-lengths, this implies that:
BranchPoint
is a well-defined point in the Inertial
-frame.BranchPoint
. In fact, except for the signs of \(\hat{s}\) and \(\hat{r}\), the frames of all the Lanes
will have the same orientation and scale.Lanes
\(J\) and \(K\) joined at a BranchPoint
located at the finish end of \(J\), then a position \((s_\text{max,J}, r, h)_J\) in \(J\) will map to either \((0, r, h)\) or \((s_\text{max,K}, -r, h)_K\) in \(K\) (depending on which end of \(K\) is at the BranchPoint
).Given point (2) above, one can imagine multiple Lanes
converging on one side of a BranchPoint
, flowing smoothly through it, and diverging into other Lanes
on the other side. If one considers the "outward-traveling tangent vector" of each Lane
, then the Lanes
can be grouped by common orientation of outward-traveling tangent vector into at most two groups. Thus, a BranchPoint
fundamentally has two sides to it. The sides are arbitrary, so we label them with the arbitrary names "A" and "B". With respect to a specific Lane
\(J\), regardless of which side \(J\) is on (be it A or B):
Lanes
on the "same side" as \(J\) are the confluent lanes of \(J\);Lanes
on the "other side" are the ongoing lanes of \(J\).TODO: figure with sample branch-point topologies:
- 1:1 — simple continuation of one lane onto another;
- 1:2 — a split of one lane to two;
- 1:3 — a split of one to three, e.g., paths through an intersection with left and right turns available;
- 2:2 — a merge/split, e.g., entering and/or exiting a roundabout;
- 1:0 — you've reached the end of the road, my friend.
A BranchPoint
bears one additional element of information. For each Lane
, one of its ongoing Lanes
may optionally be named as its default-branch. This serves as a semantic hint about the structure of the road. The default-branch represents the notion of "which
branch should I choose in order to continue straight ahead" (5). For example, when entering a 4-way intersection, a Lane
may terminate with three ongoing branches: turning left, going straight, and turning right; the "go straight" branch would be designated the default-branch. Likewise, at a split in a highway, one fork might be considered the same highway, whereas the other is considered an exit. (Also, note that default-branch relationships between Lanes
need not be symmetric.)
(3): This means a Lane
has precisely two BranchPoints
, except for the peculiar case of a Lane
which loops around and connects to itself, at a single BranchPoint
.
(4): BranchPoint
with only a single Lane
attached to it is basically a dead-end.
(5): At the finish end of a Lane
, this is just the tangent of \(C_L\); at the start end of a Lane
, it's the negative of the tangent, pointing in the \(-s\) direction instead of the \(+s\) direction.
In real roads, the pavement is often divided into multiple adjacent lanes of travel; in maliput
, adjacent Lanes
are grouped together into Segments
. The basic idea is that a Segment
corresponds to a longitudinal stretch of pavement, and each Lane
in that Segment
presents a different \((s,r,h)\) parameterization of that same pavement.
We would like for the segment-bounds of each Lane
to map to the same extent of physical space in the Inertial
-frame, but that isn't always possible due to the geometric constraints of parallel curves. However, we do require that the union of the segment-bounds of all Lanes
in a Segment
is simply-connected. This means that:
Segment
doesn't have any "holes" in its segment space (e.g., no impassable monument in the middle of the road);Lane
-frame to a position in another Lane
-frame, though it may require expressing intermediate steps in other Lanes
to do it.Within a Segment
, we only allow the intersection of two Lane
centerlines (such as a lane merge/split) to occur at the endpoints of the Lanes
, which further implies that it may occur only at a BranchPoint
. This allows us to impose another constraint on Lanes
in a Segment
: they must be oriented and shaped such that there is a consistent "right-to-left" ordering in terms of increasing \(r\). In other words, within a Segment
:
Lane
\(K\) is considered "left of" Lane
\(J\) if and only if there exists a point on the centerline \(C_{K}\) of \(K\) that has a position with \(r > 0\) in the Lane
-frame of \(J\). \(K\) is "right
of" \(J\) if and only if a point exists on \(C_{K}\) with position \(r < 0\) in the frame of \(J\).Lane
\(K\) is to the left of Lane
\(J\), then \(J\) must be to the right of \(K\).Lanes
\(J\) and \(K\), \(K\) must be either to the left or to the right of \(J\), and may not be both. A consequence of this ((2) in particular) is that the /start/ and /finish/ ends of all the Lanes
in a Segment
are grouped together respectively so that the Lanes
are generally "pointing in the same direction". Given the consistent ordering, we index the Lanes
in a Segment
with unique integers, beginning with zero for the rightmost Lane
and increasing leftward.It is possible for multiple Segments
to cover the same pavement. In fact, that is how intersections are represented, by criss-crossing Segments
which define the different paths through an intersection. Overlapping Segments
also occur where the road merges or diverges, such as on-ramps, exit ramps, traffic circles, and a road that splits to go around an impassable monument.
Segments
which map to intersecting volumes in the Inertial
-frame (in terms of the union of the segment-bounds of their Lanes
) are grouped together into a Junction
. The primary (sole?) purpose of a Junction
is to indicate that objects in its component Segments
may spatially interact with each other (e.g., collide!). Conversely, if two Segments
belong to two distinct Junction
, then objects within their respective segment-bounds should /not/ be touching. (Note that in considering intersection, we ignore the overlaps that may occur where Segments
join end-to-end via their Lanes
.)
Every Segment
must belong to one and only one Junction
, and every Junction
must contain at least one Segment
.
When designing/implementing a RoadGeometry
, it is good practice to structure the Segments
to minimize the spatial extent of Junction
. For example, a single long Segment
which crosses through two intersections would cause both intersections to belong to the same Junction
. It would be better to split that single Segment
into three: one crossing each intersection and one in-between that joins those two end-to-end, resulting in three independent Junction
that are better localized.
TODO: Explain semantics of object ID's. (cross-referencing, tiling, debugging, visualization)
TODO: Reference to
maliput::api
doxygen.
InertialPosition
LanePosition
RoadPosition
Junctions
BranchPoints
linear_tolerance
angular_tolerance
scale_length
RoadGeometry
, component Junctions
Junction
, component Lanes
Lane
-frame orientation \(Q: (s,r,h) \mapsto \text{orientation of }(\hat{s},\hat{r},\hat{h})\)Segment
, associated BranchPoints
, and left/right Lanes
, to traverse the object graph.Lanes
on each side ("A" versus "B")Lanes
for a given Lane
Lanes
for a given Lane
Lane
) for a given Lane
RoadGeometry
A RoadRulebook
(see figure ) expresses the semantic "rules of the road" for a road network, as rule elements associated to components of a RoadGeometry
. In a real, physical road network, road rules are typically signaled to users via signs or striping, though some rules are expected to be prior knowledge (e.g., "We drive on the
right-hand side here."). RoadRulebook
abstracts away from both the physical artifacts and the symbolic state of such signals, and directly represents the intended use of a road network at a semantic level.
We define three levels of knowledge of rules of the road:
The RoadRulebook
interface only concerns the semantic level, which is the level required to provide oracular /ado/ cars with interesting interactive behaviors. (Future API's may be developed to express the sensory and symbolic levels of expression, and to coordinate between all three as required.)
There are two rule APIs. One that is based on static types which is deprecated, and the other one which relies on just two C++ distinct types but allows further customization and extension by API users. In the following sections, the two APIs are described.
There are three rule C++ types: Rule
, DiscreteValueRule
and RangeValueRule
. The parent type, Rule
, helps to hold the basic information and semantic relationships with other rules, and other entities in the world, like light bulbs. DiscreteValeRule
is a rule type thought for discrete states, comprising from string based representations to numeric ones. On the other hand, RangeValueRule
completes the universe of rule types by supporting numeric ranges in which certain magnitudes may vary.
Each rule instance may have one or multiple states which are Rule::State
and its customized implementations DiscreteValueRule::DiscreteValue
and RangeValueRule::Range
. These states are defined by common attributes like other related rules (for increased semantics and hierarchies), severity levels (to moderate the action of agents), related unique IDs (thought for traffic light bulb identification with the rule state itself) and the value they hold (either a string representation or a numeric range).
Rule state dynamics, i.e. the change of DiscreteValueRule::DiscreteValue
and RangeValueRule::Range
to another one for each rule is controlled by state providers. Only interfaces for DiscreteValueRuleStateProvider
and RangeValueRuleStateProvider
are defined, meaning that custom implementations are delegated to designers so as to control state transition behaviors in the context of a simulation. These providers include the notion of time. This is the only place where it appears due to the time agnostic nature of the vast majority of the API. "Static" rules are those with a unique configured state, but there is no direct API provisioning of that information.
Finally, each rule instance is identified by a unique ID and multiple rules may share the same rule type. The rule ID is backed by Rule::Id
and the rule type ID is backed by Rule::TypeId
. There rule type itself under this framework consists of:
DiscreteValueRule::DiscreteValue
or RangeValueRule::Range
).Given that two completely unrelated semantic rule types like the "Right-Of-Way" and "Direction-Usage" are represented by the same C++ type, DiscreteValueRule
. The possible rule states for a "Right-Of-Way" rule type and "Direction-Usage" rule type are stored in a RuleRegistry
. The RuleRegistry
safely constructs rules with types that are defined at runtime or previously in a separate location or store. At runtime, agents or generically speaking API consumers might query the possible rule states for a given rule type as well as construct rules to load into a RoadRulebook
implementation.
The majority of road networks present certain rule types that are common in terms of their semantic attributes, not necessarily in their relationships or state phasing. We can identify:
RangeValueRule
DiscreteValueRule
DiscreteValueRule
DiscreteValueRule
.These types are already provided with base implementations so consumers can quickly build up a RuleRegistry
from them. It is opt-in, which proves to be flexible enough for most use cases. Backend implementations might define their own types atop of these ones or just replace them with their own rule states and types.
A few common entities, which identify regions of the road network, occur in the various rule types:
LaneId
: unique ID of a Lane
in a RoadGeometry
;SRange
: inclusive longitudinal range \([s_0, s_1]\) between two s-coordinates;LaneSRange
: a LaneId
paired with an SRange
, describing a longitudinal range of a specific Lane
;LaneSRoute
: a sequence of LaneSRange
's which describe a contiguous longitudinal path that may span multiple end-to-end connected Lane
's;LaneIdEnd
: a pair of LaneId
and an "end" specifier, which describes either the start or finish of a specific Lane
.Note: regions are attributes of new and old rule descriptions. They define the applicability space of each rule.
The RoadRulebook
API allows to query the collection of rules by:
RoadGeometry
intersects the query region.These queries are convenient because of the properties the rules themselves have and what is interesting to a simulated agent. One important aspect of the rules are their state dynamics which are handled in a different book though.
We distinguish two kinds of state:
The RoadRulebook
design decouples static state from dynamic state. Dynamic state needs to be managed during the runtime of a simulation, and different simulation frameworks have different requirements for how they store and manage dynamic state. In particular, the drake
system framework requires that all dynamic state can be externalized and collated into a single generic state vector (called the “Context”), and the RoadRulebook
design facilitates such a scheme. Decoupling the dynamic and static state also aids development; once the (small) interface between the two is established, development of API’s for each kind of state can proceed in parallel.
RoadRulebook
is an abstract interface which provides query methods to return rule instances which match some filter parameters, e.g., rules which involve a specified Lane
. Each flavor of rule is represented by a different *Rule
class. Rules are associated to a road network by referring to components of a RoadGeometry
via component ID’s. Each rule is itself identified by a unique type-specific ID. This ID is the handle for manipulating the rule during rulebook configuration, and for associating the rule with physical / symbolic models and/or dynamic state in a simulation. A rule generally consists of static state, e.g., the speed limit as posted for a lane. Some rules may involve dynamic state as well. Any dynamic state will be provided by a separate entity, with an abstract interface for each flavor of dynamic state. For example, a RightOfWayRule
may refer to dynamic state (e.g., if it represents a traffic light) via its RightOfWayRule::Id
. An implementation of the RightOfWayStateProvider
abstract interface will, via its GetState()
method, return the current state for a given RightOfWayRule::Id
. How those states are managed and evolved over time is up to the implementation.
Road rules can generally be interpreted as restrictions on behavior, and absent any rules, behavior is unrestricted (by rules of the road). For example, if a RoadRulebook
does not provide a SpeedLimitRule
for some section of the road network, then there is no speed limit established for that section of road. Whether or not an agent follows the rules is up to the agent; RoadRulebook
merely provides the rules.
Six rule types are currently defined or proposed:
SpeedLimitRule
- speed limitsRightOfWayRule
- control of right-of-way / priority on specific routesDirectionUsageRule
- direction-of-travel specificationLaneChangeRule
- adjacent-lane transition restrictionsOngoingRouteRule
- turning restrictionsPreferentialUseRule
- lane-based vehicle-type restrictions (e.g., HOV lanes)A SpeedLimitRule
describes speed limits on a longitudinal range of a Lane. It comprises:
LaneSRange
)RightOfWayRule
describes which vehicles have right-of-way (also known as "priority"). Note that "right of way" does not mean "right
to smash through obstacles". A green light means that other cars should not enter an intersection, but the light turning green will not magically clear an intersection. Even after acquiring the right-of-way, a vehicle should still respect the physical reality of its environment and operate in a safe manner. When operating on intersecting regions of the road network. In the real world, such rules are typically signaled by stop signs, yield signs, and traffic lights, or are understood as implicit knowledge of the local laws (e.g., "vehicle on the right has priority at uncontrolled
intersections").
A RightOfWayRule
instance is a collection of RightOfWayRule::State
elements which all describe the right-of-way rules pertaining to a specific zone
in the road network. The elements of a RightOfWayRule
are:
id | unique RightOfWayRule::Id |
zone | LaneSRoute |
zone_type | ZoneType enum {StopExcluded, StopAllowed} |
states | set of State mapped by State::Id |
The zone
is a directed longitudinal path in the road network, represented as a LaneSRoute
; the rule applies to any vehicle traversing forward through the zone
. The zone_type
specifies whether or not vehicles are allowed to come to a stop within the zone
. If the type is StopExcluded
, then vehicles should not enter the zone
if they do not expect to be able to completely transit the zone
while they have the right-of-way, and vehicles should continue to transit and exit the zone
if they lose the right-of-way while in the zone
. StopExcluded
implies a "stop line" at the beginning of the zone
. StopAllowed
has none of these expectations or restrictions.
Each State
comprises:
id | State::Id (unique within the context of the rule instance) |
type | State::Type enum: {Go, Stop, StopThenGo} |
yield_to | list of RightOfWayRule::Id |
The state's type
indicates whether a vehicle can Go (has right-of-way), must Stop (does not have right-of-way), or must StopThenGo (has right-of-way after coming to a complete stop). The Go and StopThenGo types are modulated by yield_to
, which is a (possibly empty) list of references to other rule instances whose right-of-way supersedes this rule. A vehicle subject to a non-empty yield_to
list does not necessarily have to stop, but its behavior should not hamper or interfere with the motion of vehicles which are controlled by rules in the yield_to
list.
Only one State
of a rule may be in effect at any given time. A rule instance which defines only a single State
is called a static rule; its meaning is entirely static and fixed for all time. Conversely, a right-of-way rule instance with multiple State
elements is a dynamic rule. Although the collection of possible State
's of a dynamic rule are fixed and described by the rule instance, knowing which State
is in effect at any given time requires querying a RightOfWayStateProvider
.
RightOfWayStateProvider
is an abstract interface that provides a query method that accepts a RightOfWayRule::Id
and returns a result containing:
current_id | State::Id |
next_id | std::optional State::Id |
next.duration_until | std::optional double |
current_id
is the current State
of the rule. next_id
is the next State
of the rule, if a transition is anticipated and the next state is known. next.duration_until
is the duration, if known, until the transition to the known next state.
Following are discussions on RightOfWayRule
configurations for a few example scenarios.
Example: Uncontrolled Midblock Pedestrian Crosswalk
Figure illustrates a very simple scenario:
With only one zone and no changing signals, a single, static RightOfWayRule
is required:
Rule + Zone | zone_type | State id | type | yield_to |
---|---|---|---|---|
"North" | *StopExcluded* | "static" | *Go* | — |
The State::Id
chosen here ("static") is arbitrary.
The zone is a LaneSRoute
spanning from the southern edge of the crosswalk to the northern edge, with zone-type StopExcluded, which means that stopping within the zone is not allowed. The single state has type Go, which means that vehicles have the right-of-way to proceed. (Note that "when it is safe to do so" is always implied with any rule.) Furthermore, that single state has an empty yield_to
list, which means no intersecting paths have priority over this one. (In fact, there are no intersecting paths.)
This is a pretty trivial rule, since it has a single state which is always "Go". However, it serves to capture the requirement that when a vehicle does stop, it should avoid stopping in the crosswalk.
Note that a more complete scenario, which actually modeled pedestrian traffic, would likely represent the crosswalk as a lane of its own (intersecting the vehicular lane) and the "North" rule would specify yielding to that crosswalk lane via the yield_to
element.
Example: One-way Side Street onto Two-Lane Artery
artery."
Figure is a scenario with an intersection:
With four zones and no changing signals, four static rules are required. The rules have been labeled by a combination of the initial heading and the turn direction of their paths. (E.g., "NB/Left" refers to "the northbound path that turns left".) All the zones are of the StopExcluded type, so that detail has been omitted from the rule table:
Rule + Zone | State id | type | yield_to |
---|---|---|---|
"EB/Straight" | "static" | *Go* | — |
"WB/Straight" | "static" | *Go* | — |
"NB/Right" | "static" | *StopThenGo* | "EB/Straight" |
"NB/Left" | "static" | *StopThenGo* | "EB/Straight", "WB/Straight" |
The State::Id
's chosen here ("static") are arbitrary.
As in the earlier Pedestrian Crosswalk example, the static Go rules of the eastbound and westbound paths show that they always have the right-of-way, but vehicles are still required to avoid stopping in the intersection. Traffic turning right onto the artery (following the "NB/Right" path) must stop at the stop sign, and then yield to any eastbound traffic. Traffic turning left onto the artery must stop and then yield to both eastbound and westbound traffic.
Example: Protected/Permitted Left Turn
Figure provides a more complex scenario with a dynamic signal-controlled intersection:
With seven zones, seven rule instances are required. The rules have been labeled by a combination of the initial heading and the turn direction of their paths. (E.g., "NB/Left" refers to "the northbound path that turns left".) All the zones are of the /StopExcluded/ type, so that detail has been omitted from the rule table:
Rule + Zone | State id | type | yield_to |
---|---|---|---|
"NB/Right" | "Red" | *StopThenGo* | "EB/Straight" |
"Green" | *Go* | — | |
"NB/Straight" | "Red" | *Stop* | — |
"Green" | *Go* | — | |
"NB/Left" | "Red" | *Stop* | — |
"Green" | *Go* | — | |
"EB/Straight" | "Red" | *Stop* | — |
"Green" | *Go* | — | |
"EB/Left" | "Red" | *Stop* | — |
"Green" | *Go* | — | |
"FlashingYellow" | *Go* | "WB/Straight", "WB/Right" | |
"WB/Right" | "Red" | *StopThenGo* | "NB/Straight", "EB/Left" |
"Green" | *Go* | — | |
"WB/Straight" | "Red" | *Stop* | — |
"Green" | *Go* | — | |
The State::Id
's have been chosen to loosely match the states of the corresponding traffic signals. (Note that typically a "yellow light" confers the same right-of-way as a "green light"; the only difference is that the yellow indicates that a transition to red is imminent.)
Each rule has at least two states. The straight-ahead rules ( *
/Straight ) and the northbound left-turning rule ( NB/Left ) are quite straightforward: either "Stop" with no right-of-way or "Go" with full right-of-way. The other turning rules are a bit more interesting.
Since "Right Turn on Red" is allowed, both the "NB/Right" and "WB/Right" rules have StopThenGo states (instead of Stop states) that must yield to other traffic. "NB/Right" must yield to eastbound traffic, and "WB/Right" must yield to northbound traffic.
The "EB/Left" rule has two Go states. One is the protected turn state, in which the left turn is given full priority over oncoming westbound traffic. The other is the permitted turn state, in which the left turn must yield to westbound traffic. In the US, a possible traffic light configuration for such an intersection would signal the protected turn by a solid green arrow, and the permitted turn by a flashing yellow arrow.
Example: Freeway Merge
Figure is a scenario with a freeway merge:
This is a static scenario with two static rules:
Rule + Zone | zone_type | State id | type | yield_to |
---|---|---|---|---|
"Freeway" | StopAllowed | "static" | *Go* | — |
"Entrance" | StopAllowed | "static" | *Go* | "Freeway" |
The State::Id
's chosen here ("static") are arbitrary.
The only constraint encoded by these two rules is that the "Entrance" traffic should yield to the "Freeway" traffic. Note that unlike previous examples, both zones in this scenario have a zone-type of StopAllowed
. That means there are no "stop lines" (real or implicit) and no exclusion zones that are expected to be left unblocked by stopped traffic. Both rules' static states are of type Go, as well; neither path is expected to stop. Ideally, the entrance traffic never stops, but instead speeds up to seamlessly merge into the freeway flow.
TODO
DirectionUsageRule
:
DirectionUsageRule
: Direction Usage
Captures allowed direction-of-travel.
LaneSRange
)TODO
LaneChangeRule
: Lane-change/Passing Restrictions
LaneChangeRule
: Lane-change/Passing Restrictions
Captures restrictions on lateral/adjacent lane transitions.
LaneSRange
)DirectionUsageRule
?TODO
OngoingRouteRule
: "Turning" Restrictions
OngoingRouteRule
: "Turning" Restrictions
Captures restrictions on longitudinal/end-to-end lane transitions.
LaneIdEnd
LaneIdEnd
TODO
PreferentialUseRule
: Vehicle Restrictions
PreferentialUseRule
: Vehicle Restrictions
Captures vehicle-type traffic restrictions.
LaneSRange
)DirectionUsageRule
, because lane usage/direction might be specified per vehicle type?As explained before, rule state dynamics are complex enough to be modeled within the very same Rule
type. Also, the RoadRulebook
falls short to provide query support for the state transition of the Rules it can fetch. maliput
models the sequencing of rule states and traffic lights' bulbs as a ring of Phases
. Each Phase
holds a dictionary of rule IDs to rule states (DiscreteValues
) and related bulb IDs (UniqueBulbIds
) to the bulb state (BulbState
).
Phases
have an implicit rule co-location constraint. Sequencing of Phases
that do not share the same region are designer's responsibility. The API does not provide any further enhanced semantics to deal with such case. However, the ordered sequence of co-located Phases
is captured by a PhaseRing
. Phases
are stored in PhaseRings
which cannot be empty. They may have only one Phase
though, meaning that it is self connected or it never ends.
NOTE: Intra-
Phase
relationship betweenRule::Id
andUniqueBulbId
can be discovered by the actualDiscreteValue
's related unique IDs by the agent.
The PhaseRing
acts as a container of all the related Phases
in a sequence. A designer might query them by the Phase::Id
or the next Phases
, but no strict order should be expected. Instead, PhaseProvider
offers an interface to obtain the current and next Phase::Ids
for a PhaseRing
. Custom time based or event driven behaviors could be implemented for this interface. Similarly to the rules, there are convenient "manual" implementations to exercise the interfaces in integration examples.
Traffic lights physically come in various shapes and configurations. With a set of bulbs (from now on BulbGroups
and Bulbs
) that are semantically related and serve many road lanes simultaneously. We are not able to capture all variations of configurations, but the API proposes a generic enough abstraction that comprises most of the use cases that involve the physical properties of the TrafficLights
, their BulbGroups
and each Bulb
in them.
Bulbs
can be round or arrows, have an orientation and position relative to the parent BulbGroup
and a specific color. At certain moment, they can be on, off or blinking. Each Bulb
occupies a volume defined with a bounding box.
A collection of Bulbs
compose a BulbGroup
. Each BulbGroup
has a pose relative to the TrafficLight
they are part of.
Finally, a TrafficLight
is composed of a set of BulbGroups
. It is set in a pose (position and orientation) in the Inertial Frame. Once it is built, both its BulbGroups
and Bulbs
are uniquely identified by composing the parent (TrafficLight::Id
), child (BulbGroup::Id
) and grandchild (Bulb::Id
) IDs. Those compound IDs are represented by UniqueBulbId
and UniqueBulbGroupId
types.
TrafficLights
can be obtained via TrafficLightBook
, another interface to which offers queries by TrafficLight::Id
and to retrieve all TrafficLights
.
The inherent complexity of the rule dynamics require multiple interfaces and and concrete implementations to be setup in favor of describing the traffic dynamics and adapt to multiple scenarios. In favor of reducing the complexity of the queries, the Intersection
aggregates multiple disperse IDs and related entities that would require many queries to different books and state providers.
To obtain the Intersection
the agent is immerse, it can use the IntersectionBook
which provides multiple query semantics to retrieve the right one:
Intersection::Id
TrafficLight::Id
DiscreteValueRule::Id
Intersections
RightOfWayRule::Id
TODO Furniture and Physical Features
Furniture and Physical Features
Provide a database of physical features with spatial location and extent.
In many cases these are related to rules in the RoadRulebook
(e.g., signs and stripes are indicators for rules of the road).