AutomotiveSimulator.AccelDesangType
AccelDesang

An action type with a longitudinal acceleration and a desired heading angle

Fields

  • a::Float64 longitudinal acceleration [m/s^2]
  • ϕdes::Float64 desired heading angle
AutomotiveSimulator.AccelSteeringAngleType
AccelSteeringAngle

Allows driving the car in a circle based on the steering angle If steering angle less than threshold 0.01 radian, just drives straight

Fields

  • a::Float64 longitudinal acceleration [m/s^2]
  • δ::Float64 Steering angle [rad]
AutomotiveSimulator.AccelTurnrateType
AccelTurnrate

An action type with a longitudinal acceleration and a turn rate

Fields

  • a::Float64 longitudinal acceleration [m/s^2]
  • ω::Float64 desired turn rate [rad/sec]
AutomotiveSimulator.BicycleModelType
BicycleModel
BicycleModel(def::VehicleDef; a::Float64 = 1.5, b::Float64 = 1.5)

Vehicle definition representing the bicycle model

Fields

  • def::VehicleDef
  • a::Float64 distance between cg and front axle [m]
  • b::Float64 distance between cg and rear axle [m]
AutomotiveSimulator.CPAMemoryType
CPAMemory

A structure to cache the bounding boxes around vehicle. It is part of the internals of the Minkowski collision checker.

Fields

  • vehA::ConvexPolygon bounding box for vehicle A
  • vehB::ConvexPolygon bounding box for vehicle B
  • mink::ConvexPolygon minkowski bounding box
AutomotiveSimulator.CollisionCheckResultType
CollisionCheckResult

A type to store the result of a collision checker

Fields

  • is_colliding::Bool
  • A::Int64 # index of 1st vehicle
  • B::Int64 # index of 2nd vehicle
AutomotiveSimulator.ConvexPolygonType
ConvexPolygon
ConvexPolygon(npts::Int)
ConvexPolygon(pts::Vector{VecE2{Float64}})

Mutable structure to represent a convex polygon. It is used by the Minkowski sum collision checker

Fields

  • pts::Vector{VecE2{Float64}}
  • npts::Int
AutomotiveSimulator.CrossingPhaseType
CrossingPhase

Crossing phases for SidewalkPedestrianModel.

For a crossing pedestrian, phases go: -2, -1, 0, 1 For a non-crossing pedestrian that pauses at the crosswalk, phases go: -2, -1, 1 For a non-crossing pedestrian that does not pause at the crosswalk, phases go: -2, 1

Model based on Feliciani et al (2017) - A simulation model for non-signalized pedestrian crosswalks based on evidence from on field observation.

AutomotiveSimulator.CurveIndexType
CurveIndex{I <: Integer, T <: Real}

Given a Curve object curve one can call curve[ind] where ind is a CurveIndex. The field t can be used to interpolate between two points in the curve.

Fields

  • i::I` index in the curve , ∈ [1:length(curve)-1]
  • t::T ∈ [0,1] for linear interpolation
AutomotiveSimulator.CurveProjectionType
CurveProjection{I <: Integer, T <: Real}

The result of a point projected to a Curve

Fields

  • ind::CurveIndex{I, T}
  • t::T lane offset
  • ϕ::T lane-relative heading [rad]
AutomotiveSimulator.CurvePtType
CurvePt{T}

describes a point on a curve, associated with a curvature and the derivative of the curvature

  • pos::VecSE2{T} # global position and orientation
  • s::T # distance along the curve
  • k::T # curvature
  • kd::T # derivative of curvature
AutomotiveSimulator.DriverModelType
DriverModel{DriveAction}

A DriverModel represents a specific driving behavior. It specifies the action taken by the agent at a given scene. The ation will be of type DriveAction. It can be interpreted as a distribution, the likelihood of taking a certain action in a given scene. The DriverModel type is an abstract type! Custom driver models should inherit from it.

AutomotiveSimulator.EntityType
Entity{S,D,I}

Immutable data structure to represent entities (vehicle, pedestrian, ...). Entities are defined by a state, a definition, and an id. The state of an entity usually models changing values while the definition and the id should not change.

Constructor

Entity(state, definition, id)

Copy constructor that keeps the definition and id but changes the state (a new object is still created):

Entity(entity::Entity{S,D,I}, s::S)

Fields

  • state::S
  • def::D
  • id::I
AutomotiveSimulator.EntityActionType

Mapping from actions to entity ids. The main use case is for keeping track of the action history in the same way as the scene history in the simulate! function.

Initialize as

EntityAction(a, id)

where a is an action which can be used to propagate entities. id is the entity identifier.

AutomotiveSimulator.EntitySceneType
EntityScene{S,D,I} = Scene{Entity{S,D,I}}

Alias for Scene when the entities in the scene are of type Entity

Constructors

  • EntityScene(::Type{S},::Type{D},::Type{I}) where {S,D,I}
  • EntityScene(::Type{S},::Type{D},::Type{I},capacity::Int)
AutomotiveSimulator.FrenetType
Frenet

Represents a vehicle position and heading in a lane relative frame.

Constructors

  • Frenet(roadind::RoadIndex, roadway::Roadway; t::Float64=0.0, ϕ::Float64=0.0)
  • Frenet(roadproj::RoadProjection, roadway::Roadway)
  • Frenet(lane::Lane, s::Float64, t::Float64=0.0, ϕ::Float64=0.0)
  • Frenet(posG::VecSE2, roadway::Roadway)
  • Frenet(posG::VecSE2, lane::Lane, roadway::Roadway)

Fields

  • roadind: road index
  • s: distance along lane
  • t: lane offset, positive is to left. zero point is the centerline of the lane.
  • ϕ: lane relative heading
AutomotiveSimulator.FrenetRelativePositionType
FrenetRelativePosition

Contains information about the projection of a point on a lane. See get_frenet_relative_position.

Fields

  • origin::RoadIndex original roadindex used for the projection, contains the target lane ID.
  • target::RoadIndex roadindex reached after projection
  • Δs::Float64 longitudinal distance to the original roadindex
  • t::Float64 lateral distance to the original roadindex in the frame of the target lane
  • ϕ::Float64 angle with the original roadindex in the frame of the target lane
AutomotiveSimulator.IntelligentDriverModelType
IntelligentDriverModel <: LaneFollowingDriver

The Intelligent Driver Model. A rule based driving model that is governed by parameter settings. The output is an longitudinal acceleration.

Here, we have extended IDM to the errorable IDM. If a standard deviation parameter is specified, then the output is a longitudinal acceleration sampled from a normal distribution around the non-errorable IDM output.

Fields

  • a::Float64 = NaN the predicted acceleration i.e. the output of the model
  • σ::Float64 = NaN allows errorable IDM, optional stdev on top of the model, set to zero or NaN for deterministic behavior
  • k_spd::Float64 = 1.0 proportional constant for speed tracking when in freeflow [s⁻¹]
  • δ::Float64 = 4.0 acceleration exponent
  • T::Float64 = 1.5 desired time headway [s]
  • v_des::Float64 = 29.0 desired speed [m/s]
  • s_min::Float64 = 5.0 minimum acceptable gap [m]
  • a_max::Float64 = 3.0 maximum acceleration ability [m/s²]
  • d_cmf::Float64 = 2.0 comfortable deceleration m/s²
  • d_max::Float64 = 9.0 maximum deceleration m/s²
AutomotiveSimulator.LaneType
Lane

A driving lane on a roadway. It identified by a LaneTag. A lane is defined by a curve which represents a center line and a width. In addition it has attributed like speed limit. A lane can be connected to other lane in the roadway, the connection are specified in the exits and entrances fields.

Fields

  • tag::LaneTag
  • curve::Curve
  • width::Float64 [m]
  • speed_limit::SpeedLimit
  • boundary_left::LaneBoundary
  • boundary_right::LaneBoundary
  • exits::Vector{LaneConnection} # list of exits; put the primary exit (at end of lane) first
  • entrances::Vector{LaneConnection} # list of entrances; put the primary entrance (at start of lane) first
AutomotiveSimulator.LaneBoundaryType
LaneBoundary

Data structure to represent lanes boundaries such as double yellow lines.

Fields

- `style::Symbol` ∈ :solid, :broken, :double
- `color::Symbol` ∈ :yellow, white
AutomotiveSimulator.LaneConnectionType
LaneConnection{I <: Integer, T <: Real}

Data structure to specify the connection of a lane. It connects mylane to the point target. target would typically be the starting point of a new lane.

  • downstream::Bool
  • mylane::CurveIndex{I,T}
  • target::RoadIndex{I,T}
AutomotiveSimulator.LaneFollowingAccelType
LaneFollowingAccel

Longitudinal acceleration. The resulting vehicle velocity is capped below at 0 (i.e. standstill). Negative velocities are not allowed.

Fields

  • a::Float64 longitudinal acceleration [m/s^2]
AutomotiveSimulator.LaneTagType
LaneTag

An identifier for a lane. The lane object can be retrieved by indexing the roadway by the lane tag:

tag = LaneTag(1, 2) # second lane segment 1
lane = roadway[tag] # returns a Lane object

Fields

  • segment::Int64 segment id
  • lane::Int64 index in segment.lanes of this lane
AutomotiveSimulator.LatLonAccelType
LatLonAccel

Acceleration in the frenet frame

Fields

  • a_lat::Float64 Lateral acceleration [m/s^2]
  • a_lon::Float64 Longitudinal acceleration [m/s^2]
AutomotiveSimulator.MOBILType
MOBIL

See Treiber & Kesting, 'Modeling Lane-Changing Decisions with MOBIL'

Constructor

MOBIL(;kwargs...) The keyword arguments are the fields highlighted below.

Fields

  • dir::Int = DIR_MIDDLE
  • mlon::LaneFollowingDriver=IntelligentDriverModel()
  • safe_decel::Float64=2.0
  • politeness::Float64=0.35
  • advantage_threshold::Float64=0.1
AutomotiveSimulator.NeighborLongitudinalResultType
NeighborLongitudinalResult

A structure to retrieve information about a neihbor in the longitudinal direction i.e. rear and front neighbors on the same lane. If the neighbor index is equal to nothing it means there is no neighbor.

Fields

  • ind::Union{Nothing, Int64} index of the neighbor in the scene
  • Δs::Float64 positive distance along the lane between vehicles positions
AutomotiveSimulator.PedestrianLatLonAccelType
PedestrianLatLonAccel

Pedestrian walking action. Acceleration in the Frenet frame, along with desired lane after crossing the street.

Fields

  • a_lat::Float64 lateral acceleration [m/s^2]
  • a_lon::Float64 longitudinal accelaration [m/s^2]
  • lane_des::Lane desired lane to move to
AutomotiveSimulator.PrincetonDriverType
PrincetonDriver <: LaneFollowingDriver

A lane following driver model that controls longitudinal speed by following a front car.

Fields

  • a::Float64
  • σ::Float64 = NaN optional stdev on top of the model, set to zero or NaN for deterministic behavior
  • k::Float64 = 1.0 proportional constant for speed tracking [s⁻¹]
  • v_des::Float64 = 29.0 desired speed [m/s]
AutomotiveSimulator.ProportionalLaneTrackerType
ProportionalLaneTracker

A controller that executes the lane change decision made by the lane change models

Constructors

ProportionalLaneTracker(;σ::Float64 = NaN,kp::Float64 = 3.0,kd::Float64 = 2.0)

Fields

  • a::Float64 = NaN predicted acceleration
  • σ::Float64 = NaN optional stdev on top of the model, set to zero or NaN for deterministic behavior
  • kp::Float64 = 3.0 proportional constant for lane tracking
  • kd::Float64 = 2.0 derivative constant for lane tracking
AutomotiveSimulator.ProportionalSpeedTrackerType
ProportionalSpeedTracker <: LaneFollowingDriver

Longitudinal proportional speed control.

Fields

  • a::Float64 = NaN predicted acceleration
  • σ::Float64 = NaN optional stdev on top of the model, set to zero or NaN for deterministic behavior
  • k::Float64 = 1.0 proportional constant for speed tracking [s⁻¹]
  • v_des::Float64 = 29.0 desired speed [m/s]
AutomotiveSimulator.RoadIndexType
RoadIndex{I <: Integer, T <: Real}

A data structure to index points in a roadway. Calling roadway[roadind] will return the point associated to the road index.

Fields

  • ind::CurveIndex{I,T} the index of the point in the curve
  • tag::LaneTag the lane tag of the point
AutomotiveSimulator.RoadProjectionType
RoadProjection{I <: Integer, T <: Real}

represents the projection of a point on the roadway

Fields

  • curveproj::CurveProjection{I, T}
  • tag::LaneTag
AutomotiveSimulator.RoadSegmentType
RoadSegment{T}

a list of lanes forming a single road with a common direction

Fields

  • id::Int64
  • lanes::Vector{Lane{T}} lanes are stored right to left
AutomotiveSimulator.RoadwayType
Roadway

The main datastructure to represent road network, it consists of a list of RoadSegment

Fields

  • segments::Vector{RoadSegment}
AutomotiveSimulator.SceneType
Scene{E}

Container to store a list of entities. The main difference from a regular array is that its size is defined at construction and is fixed. (push! is O(1))

Constructors

  • Scene(arr::AbstractVector; capacity::Int=length(arr))
  • Scene(::Type{E}, capacity::Int=100) where {E}

Fields

To interact with Scene object it is preferable to use functions rather than accessing the fields directly.

  • entities::Vector{E}
  • n::Int current number of entities in the scene
AutomotiveSimulator.SidewalkPedestrianModelType
SidewalkPedestrianModel

Walks along the sidewalk until approaching the crosswalk. Waits for the cars to pass, then crosses.

Fields

  • timestep::Float64
  • phase::Int = APPROACHING
  • ttc_threshold::Float64 = clamp(rand(Normal(4.0, 2.5)), 1.0, Inf)
  • crosswalk::Lane = Lane()
  • sw_origin::Lane = Lane()
  • sw_dest::Lane = Lane()
  • a::PedestrianLatLonAccel = PedestrianLatLonAccel(0.0, 0.0, sw_origin) makes you turn, left/right
  • σ::Float64 = NaN optional stdev on top of the model, set to zero or NaN for deterministic
  • v_des_approach::Float64 = clamp(rand(Normal(1.28, 0.18)), 0.0, Inf) Based on Feliciani et al. results
  • v_des_appraise::Float64 = clamp(rand(Normal(0.94, 0.21)), 0.0, Inf)
  • v_des_cross::Float64 = clamp(rand(Normal(1.35, 0.18)), 0.0, Inf)
  • ped_accel::Float64 = 0.30
  • ped_decel::Float64 = -0.50
AutomotiveSimulator.SpeedLimitType
SpeedLimit

Datastructure to represent a speed limit

Fields

  • lo::Float64 [m/s] lower speed limit
  • hi::Float64 [m/s] higher speed limit
AutomotiveSimulator.StaticDriverType
StaticDriver{A,P<:ContinuousMultivariateDistribution} <: DriverModel{A}

A driver model where actions are always sampled by the same distribution specified by the field distribution.

Fields

  • distribution::P
AutomotiveSimulator.Tim2DDriverType
Tim2DDriver

Driver that combines longitudinal driver and lateral driver into one model.

Constructors

Tim2DDriver(;kwargs...) The keywords argument are the fields described below.

Fields

  • mlon::LaneFollowingDriver = IntelligentDriverModel() Longitudinal driving model
  • mlat::LateralDriverModel = ProportionalLaneTracker() Lateral driving model
  • mlane::LaneChangeModel =TimLaneChanger Lane change model
AutomotiveSimulator.TimLaneChangerType
TimLaneChanger

A simple lane change behavior that changes lanes whenever the lead car is going slower than our desired speed. Lane changes are made when there is an available lane, fore/rear gaps exceed our thresholds, we are faster than a rear vehicle in the target lane, and any lead vehicle in the target lane is faster than we can currently go.

Has not been published anywhere, so first use in a paper would have to describe this. See MOBIL if you want a lane changer you can cite.

Constructors

TimLaneChanger(v_des::Float64=29.0, threshold_fore::Float64 = 50.0,threshold_lane_change_gap_fore::Float64 = 10.0, threshold_lane_change_gap_rear::Float64 = 10.0,dir::Int=DIR_MIDDLE)

Fields

  • dir::Int = DIR_MIDDLE the desired lane to go to eg: left,middle (i.e. stay in same lane) or right
  • v_des::Float64 = 29.0 desired velocity
  • threshold_fore::Float64 = 50.0 Distance from lead vehicle
  • threshold_lane_change_gap_fore::Float64 = 10.0 Space in front
  • threshold_lane_change_gap_rear::Float64 = 10.0 Space rear
AutomotiveSimulator.VehicleDefType
VehicleDef(;class::Float64, length::Float64, width::Float64)

Vehicle definition which contains a class and a bounding box.

AutomotiveSimulator.VehicleStateType
VehicleState

A default type to represent an agent physical state (position, velocity). It contains the position in the global frame, Frenet frame and the longitudinal velocity

constructors

VehicleState(posG::VecSE2{Float64}, v::Float64) 
VehicleState(posG::VecSE2{Float64}, roadway::Roadway, v::Float64)
VehicleState(posG::VecSE2{Float64}, lane::Lane, roadway::Roadway, v::Float64)
VehicleState(posF::Frenet, roadway::Roadway, v::Float64)

fields

  • posG::VecSE2{Float64} global position
  • posF::Frenet lane relative position
  • v::Float64 longitudinal velocity
AutomotiveSimulator.VehicleTargetPointType
VehicleTargetPoint

Defines a point on an entity that is used to measure distances. The following target points are supported and are subtypes of VehicleTargetPoint:

  • VehicleTargetPointFront
  • VehicleTargetPointCenter
  • VehicleTargetPointRear

The method targetpoint_delta(::VehicleTargetPoint, ::Entity) can be used to compute the delta in the longitudinal direction to add when considering a specific target point.

AutomotiveSimulator.Vec.get_distanceMethod
Vec.get_distance(A::Entity{S,D,I}, B::Entity{S,D,I}, mem::CPAMemory=CPAMemory()) where {D<:AbstractAgentDefinition,I}

returns the euclidean distance between A and B.

AutomotiveSimulator.Vec.lerpMethod
Vec.lerp(a::VehicleState, b::VehicleState, t::Float64, roadway::Roadway)

Perform linear interpolation of the two vehicle states. Returns a VehicleState.

AutomotiveSimulator.Vec.projMethod
Vec.proj(posG::VecSE2, curve::Curve)

Return a CurveProjection obtained by projecting posG onto the curve

AutomotiveSimulator.Vec.projMethod
proj(posG::VecSE2{T}, lane::Lane, roadway::Roadway; move_along_curves::Bool=true) where T <: Real

Return the RoadProjection for projecting posG onto the lane. This will automatically project to the next or prev curve as appropriate. if move_along_curves is false, will only project to lane.curve

AutomotiveSimulator.Vec.projMethod
proj(posG::VecSE2{T}, seg::RoadSegment, roadway::Roadway) where T <: Real

Return the RoadProjection for projecting posG onto the segment. Tries all of the lanes and gets the closest one

AutomotiveSimulator.Vec.projMethod
proj(posG::VecSE2{T}, seg::RoadSegment, roadway::Roadway) where T <: Real

Return the RoadProjection for projecting posG onto the roadway. Tries all of the lanes and gets the closest one

AutomotiveSimulator.accMethod
acc(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the history of acceleration of the entity of id vehid using finite differences on the velocity. The first element is missing.

AutomotiveSimulator.accfsMethod
accfs(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the history of longitudinal acceleration in the Frenet frame of the entity of id vehid using finite differences on the velocity. The first element is missing.

AutomotiveSimulator.accftMethod
accft(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the history of lateral acceleration in the Frenet frame of the entity of id vehid using finite differences on the velocity. The first element is missing.

AutomotiveSimulator.capacityMethod
capacity(scene::Scene)

returns the maximum number of entities that can be put in the scene. To get the current number of entities use length instead.

AutomotiveSimulator.collision_checkerMethod
collision_checker(veh_a::Entity, veh_b::Entity)
collision_checker(veh_a, veh_b, veh_a_def::AbstractAgentDefinition, veh_b_def::AbstractAgentDefinition)

return True if veh_a and veh_b collides. Relies on the parallel axis theorem.

AutomotiveSimulator.collision_checkerMethod
collision_checker(scene::Scene{Entity{S,D,I}}, egoid::I) where {S, D<:AbstractAgentDefinition, I}

return true if any entity in the scene collides with the entity of id egoid.

AutomotiveSimulator.dist_to_front_neighborMethod
dist_to_front_neighbor(roadway::Roadway, scene::Scene, veh::Entity)

Feature function to extract the longitudinal distance to the front neighbor (in the Frenet frame). Returns missing if there are no front neighbor.

AutomotiveSimulator.distance_toMethod
distance_to(egoid)

generate a feature function distancetoegoid.

distance_to_$egoid(roadway, scene, veh) returns the distance between veh and the vehicle of id egoid in the scene.

AutomotiveSimulator.extract_featuresMethod
extract_features(features, roadway::Roadway, scenes::Vector{<:Scene}, ids::Vector{I}) where I

Extract information from a list of scenes. It returns a dictionary of DataFrame objects.

Inputs

  • features: a tuple of feature functions. The feature types supported are EntityFeature, SceneFeature and TemporalFeature. Check the documentation for the list of available feature functions, and how to implement you own feature function.
  • roadway::Roadway : the roadway associated to the scenes.
  • scenes::Vector{<:Scene} : the simulation data from which we wish to extract information from. Each scene in the vector corresponds to one time step.
  • ids::Vector{I}: a list of entity IDs for which we want to extract the information.

Output

A dictionary mapping IDs to DataFrame objects. For a given ID, the DataFrame's columns correspond to the name of the input feature functions. The row correspond to the feature value for each scene (time history).

Example:

roadway = gen_straight_roadway(4, 100.0) 

scene_0 = Scene([
            Entity(VehicleState(VecSE2( 0.0,0.0,0.0), roadway, 10.0), VehicleDef(AgentClass.CAR, 5.0, 2.0), 1),
            Entity(VehicleState(VecSE2(10.0,0.0,0.0), roadway, 10.0), VehicleDef(AgentClass.CAR, 5.0, 2.0), 2),
        ])

scene_1 = Scene([
            Entity(VehicleState(VecSE2( 10.0,0.0,0.0), roadway, 10.0), VehicleDef(AgentClass.CAR, 5.0, 2.0), 1),
            Entity(VehicleState(VecSE2(20.0,0.0,0.0), roadway, 10.0), VehicleDef(AgentClass.CAR, 5.0, 2.0), 2),
        ])

dfs = extract_features((posgx, iscolliding), roadway, [scene_0, scene_1], [1,2])

dfs[1].posgx # history of global x position for vehicle of ID 1
AutomotiveSimulator.featuretypeMethod
featuretype(f::Function)

function used for dispatching feature types depending on the method of the feature function

AutomotiveSimulator.find_neighborMethod
find_neighbor(scene::Scene, roadway::Roawday, ego::Entity; kwargs...)

Search through lanes and road segments to find a neighbor of ego in the scene. Returns a NeighborLongitudinalResult object with the index of the neighbor in the scene and its relative distance.

Arguments

  • scene::Scene the scene containing all the entities
  • roadway::Roadway the road topology on which entities are driving
  • ego::Entity the entity that we want to compute the neighbor of.

Keyword arguments

  • lane::Union{Nothing, Lane} the lane on which to search the neighbor, if different from the ego vehicle current lane, it uses the projection of the ego vehicle on the given lane as a reference point. If nothing, returns nothing.
  • rear::Bool = false set to true to search for rear neighbor, search forward neighbor by default
  • max_distance::Float64 = 250.0 stop searching after this distance is reached, if the neighbor is further than max_distance, returns nothing
  • targetpoint_ego::VehicleTargetPoint the point on the ego vehicle used for distance calculation, see VehicleTargetPoint for more info
  • targetpoint_neighbor::VehicleTargetPoint the point on the neighbor vehicle used for distance calculation, see VehicleTargetPoint for more info
  • ids_to_ignore::Union{Nothing, Set{I}} = nothing a list of entity ids to ignore for the search, ego is always ignored.
AutomotiveSimulator.find_separating_axisMethod
find_separating_axis(poly_a::SMatrix{4, 2, Float64}, poly_b::SMatrix{4, 2, Float64})

build a list of candidate separating axes from the edges of a /!\ edges needs to be ordered

AutomotiveSimulator.front_neighbor_speedMethod
front_neighbor_speed(roadway::Roadway, scene::Scene, veh::Entity)

Feature function to extract the velocity of the front neighbor. Returns missing if there are no front neighbor.

AutomotiveSimulator.gen_bezier_curveMethod
gen_bezier_curve(A::VecSE2{T}, B::VecSE2{T}, rA::T, rB::T, nsamples::Int) where T <: Real

Generate a Bezier curve going from A to B with radii specified by rA and rB. It uses cubic interpolation. nsamples specifies the number of point along the curve between A and B. The more points, the more accurate the approximation is. This is useful to generate arcs.

AutomotiveSimulator.gen_stadium_roadwayMethod
gen_stadium_roadway(nlanes::Int; length::Float64=100.0; width::Float64=10.0; radius::Float64=25.0)

Generate a roadway that is a rectangular racetrack with rounded corners. length = length of the x-dim straight section for the innermost (leftmost) lane [m] width = length of the y-dim straight section for the innermost (leftmost) lane [m] radius = turn radius [m]

  ______________________
 /                      \ 
|                        |
|                        |
\______________________/
AutomotiveSimulator.gen_straight_curveMethod
gen_straight_curve(A::VecE2{T}, B::VecE2{T}, nsamples::Integer) where T<:Real

Returns a Curve corresponding to a straight line between A and B. nsamples indicates the number of points to place between A and B, if set to two, the curve will only contains A and B.

AutomotiveSimulator.gen_straight_roadwayFunction
gen_straight_roadway(nlanes::Int, length::Float64)

Generate a roadway with a single straight segment whose rightmost lane center starts at starts at (0,0), and proceeds in the positive x direction.

AutomotiveSimulator.gen_straight_segmentFunction
gen_straight_segment(seg_id::Integer, nlanes::Integer, length::Float64=1000.0;

Generate a straight RoadSegment with nlanes number of lanes of length length.

AutomotiveSimulator.get_by_idMethod
get_by_id(scene::EntityScene{S,D,I}, id::I) where {S,D,I}

Retrieve the entity by its id. This function uses findfirst which is O(n).

AutomotiveSimulator.get_collision_timeMethod
get_collision_time(ray::VecSE2{Float64}, poly::ConvexPolygon, ray_speed::Float64)

returns the collision time between a ray and a polygon given ray_speed

AutomotiveSimulator.get_first_collisionMethod
get_first_collision(scene::EntityScene{S,D,I}, mem::CPAMemory=CPAMemory()) where {S,D<:AbstractAgentDefinition,I}

Loops through the scene and finds the first collision between any two vehicles

AutomotiveSimulator.get_first_collisionMethod
get_first_collision(scene::EntityScene{S,D,I}, vehicle_indeces::AbstractVector{Int}, mem::CPAMemory=CPAMemory()) where {S,D<:AbstractAgentDefinition,I}

Loops through the scene and finds the first collision between any two vehicles in vehicle_indeces.

AutomotiveSimulator.get_first_collisionMethod
get_first_collision(scene::EntityScene{S,D,I}, target_index::Int, mem::CPAMemory=CPAMemory()) where {S,D<:AbstractAgentDefinition,I}

Loops through the scene and finds the first collision between a vehicle and scene[target_index]

AutomotiveSimulator.get_frenet_relative_positionMethod
get_frenet_relative_position(veh_fore::Entity, veh_rear::Entity, roadway::Roadway)

return the Frenet relative position between the two vehicles. It projects the position of the first vehicle onto the lane of the second vehicle. The result is stored as a FrenetRelativePosition.

Lower level: getfrenetrelativeposition(posG::VecSE2{Float64}, roadind::RoadIndex, roadway::Roadway; maxdistancefore::Float64 = 250.0, # max distance to search forward [m] maxdistancerear::Float64 = 250.0, # max distance to search backward [m] improvementthreshold::Float64 = 1e-4, )

Project the given point to the same lane as the given RoadIndex. This will return the projection of the point, along with the Δs along the lane from the RoadIndex. The returned type is a FrenetRelativePosition object.

AutomotiveSimulator.get_laneMethod
get_lane(roadway::Roadway, vehicle::Entity)
get_lane(roadway::Roadway, vehicle::VehicleState)

return the lane where vehicle is in.

AutomotiveSimulator.get_oriented_bounding_boxMethod
get_oriented_bounding_box(center::VecSE2{Float64}, len::Float64, wid::Float64) = to_oriented_bounding_box!(ConvexPolygon(4), center, len, wid)
get_oriented_bounding_box(veh::Entity{S,D,I}, center::VecSE2{Float64} = get_center(veh))  where {S,D<:AbstractAgentDefinition,I}

Returns a ConvexPolygon representing a bounding rectangle of the size specified by center, length, width

AutomotiveSimulator.has_nextMethod
has_next(lane::Lane)

returns true if the end of the lane is connected to another lane (i.e. if it has an exit lane)

AutomotiveSimulator.has_prevMethod
has_prev(lane::Lane)

returns true if another lane is connected to the beginning of that lane. (i.e. if it has an entrance lane)

AutomotiveSimulator.is_collidingMethod
is_colliding(A::Entity{S,D,I}, B::Entity{S,D,I}, mem::CPAMemory=CPAMemory()) where {D<:AbstractAgentDefinition,I}

returns true if the vehicles A and B are colliding. It uses Minkowski sums. is_colliding(mem::CPAMemory) returns true if vehA and vehB in mem collides.

AutomotiveSimulator.is_collision_freeMethod
is_collision_free(scene::EntityScene{S,D,I}, mem::CPAMemory=CPAMemory()) where {S,D<:AbstractAgentDefinition,I}
is_collision_free(scene::EntityScene{S,D,I}, vehicle_indeces::AbstractVector{Int}, mem::CPAMemory=CPAMemory()) where {S,D<:AbstractAgentDefinition,I}

Check that there is no collisions between any two vehicles in scene

If vehicle_indeces is used, it only checks for vehicles within scene[vehicle_indeces]

AutomotiveSimulator.isacceleratingMethod
isaccelerating(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

history of acceleration events: true when the acceleration is positive The first element is missing.

AutomotiveSimulator.isbrakingMethod
isbraking(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

history of braking events: true when the acceleration is negative. The first element is missing.

AutomotiveSimulator.iscollidingMethod
iscolliding(roadway::Roadway, scene::Scene, veh::Entity)

returns true if the vehicle is colliding with another vehicle in the scene.

AutomotiveSimulator.jerkMethod
jerk(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the jerk history of the entity of id vehid using finite differences on acceleration (which uses finite differences on velocity). The first two elements are missing.

AutomotiveSimulator.jerkfsMethod
jerkfs(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the longitudinal jerk history in the Frenet frame of the entity of id vehid using finite differences on acceleration (which uses finite differences on velocity). The first two elements are missing.

AutomotiveSimulator.jerkftMethod
jerkft(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the lateral jerk history in the Frenet frame of the entity of id vehid using finite differences on acceleration (which uses finite differences on velocity). The first two elements are missing.

AutomotiveSimulator.lane_curvatureMethod
lane_curvature(roadway::Roadway, veh::Entity)

Return the curvature of the lane at veh's position. Return missing if the curvature is NaN

AutomotiveSimulator.lane_offset_leftMethod
lane_offset_left(roadway::Roadway, veh::Entity)

returns the distance to the left lane border, if there are no left lane returns missing

AutomotiveSimulator.lane_offset_rightMethod
lane_offset_right(roadway::Roadway, veh::Entity)

returns the distance to the right lane border, if there are no right lane returns missing

AutomotiveSimulator.leftlaneMethod
leftlane(roadway::Roadway, veh::Entity)

returns the lane to the left of the lane veh is currently in, returns nothing if it does not exists

AutomotiveSimulator.leftlaneMethod
leftlane(roadway::Roadway, lane::Lane)

returns the lane to the left of lane if it exists, returns nothing otherwise

AutomotiveSimulator.move_alongMethod
move_along(vehstate::VehicleState, roadway::Roadway, Δs::Float64;
ϕ₂::Float64=vehstate.posF.ϕ, t₂::Float64=vehstate.posF.t, v₂::Float64=vehstate.v)

returns a vehicle state after moving vehstate of a length Δs along its lane.

AutomotiveSimulator.next_laneMethod
next_lane(lane::Lane, roadway::Roadway)

returns the lane connected to the end lane. If lane has several exits, it returns the first one

AutomotiveSimulator.observe!Function
observe!(model::DriverModel, scene, roadway, egoid)

Observes the scene and updates the model states accordingly.

AutomotiveSimulator.observe_from_history!Function
observe_from_history!(model::DriverModel, roadway::Roadway, trajdata::Vector{<:EntityScene}, egoid, start::Int, stop::Int)

Given a prerecorded trajectory trajdata, run the observe function of a driver model for the scenes between start and stop for the vehicle of id egoid. The ego vehicle does not take any actions, it just observe the scenes,

AutomotiveSimulator.overlapMethod
overlap(poly_a::SMatrix{4, 2, Float64}, poly_b::SMatrix{4, 2, Float64})

Check if two convex polygons overlap, using the parallel axis theorem a polygon is a nx2 matrix where n in the number of verteces http://gamemath.com/2011/09/detecting-whether-two-convex-polygons-overlap/ /!\ edges needs to be ordered

AutomotiveSimulator.polygonMethod
polygon(pos::VecSE2{Float64}, veh_def::AbstractAgentDefinition)
polygon(x::Float64,y::Float64,theta::Float64, length::Float64, width::Float64)

returns a 4x2 static matrix corresponding to a rectangle around a car centered at pos and of dimensions specified by veh_def

AutomotiveSimulator.polygon_projectionMethod
polygon_projection(poly::SMatrix{4, 2, Float64}, axis::Vector{Float64})

return the projection interval for the polygon poly over the axis axis

AutomotiveSimulator.posfFunction
posf(state)

returns the coordinates of the state in the Frenet frame. The return type is expected to be Frenet.

AutomotiveSimulator.posgFunction
posg(state)

returns the coordinates of the state in the global (world) frame. The return type is expected to be a VecSE2.

AutomotiveSimulator.posgMethod
posg(frenet::Frenet, roadway::Roadway)

projects the Frenet position into the global frame

AutomotiveSimulator.prev_laneMethod
prev_lane(lane::Lane, roadway::Roadway)

returns the lane connected to the beginning lane. If lane has several entrances, it returns the first one

AutomotiveSimulator.propagateMethod

propagate vehicle forward in time given a desired acceleration and steering angle. If steering angle higher than 0.1 radian, the vehicle drives in a circle

AutomotiveSimulator.propagateMethod
propagate(veh::Entity{VehicleState,D,I}, action::AccelDesang, roadway::Roadway, Δt::Float64; n_integration_steps::Int=4) where {D,I}

Propagate vehicle forward in time using a desired acceleration and heading angle

AutomotiveSimulator.propagateMethod
propagate(veh::Entity{S,D,I}, action::A, roadway::R, Δt::Float64) where {S,D,I,A,R}

Take an entity of type {S,D,I} and move it over Δt seconds to produce a new entity based on the action on the given roadway.

AutomotiveSimulator.rightlaneMethod
rightlane(roadway::Roadway, veh::Entity)

returns the lane to the right of the lane veh is currently in, returns nothing if it does not exists

AutomotiveSimulator.rightlaneMethod
rightlane(roadway::Roadway, lane::Lane)

returns the lane to the right of lane if it exists, returns nothing otherwise

AutomotiveSimulator.run_callbackFunction
run_callback(callback, scenes::Vector{EntityScene}, actions::Union{Nothing, Vector{A}}, roadway::Roadway, models::Dict{I, DriverModel}, tick::Int64)

Given a callback type, run_callback will be run at every step of a simulation run using simulate. By overloading the run_callback method for a custom callback type one can log information or interrupt a simulation. The run_callback function is expected to return a boolean. If true the simulation is stopped.

Inputs:

  • callback the custom callback type used for dispatch
  • scenes where the simulation data is stored, note that it is only filled up to the current time step (scenes[1:tick+1])
  • actions where the actions are stored, it is only filled up to actions[tick]
  • roadway the roadway where entities are moving
  • models a dictionary mapping entity IDs to driver models
  • tick the index of the current time step
AutomotiveSimulator.set_desired_speed!Function
set_desired_speed!(model::DriverModel, v_des::Float64)

Sets a desired speed. This method is relevant for models like IDM where the vehicle tracks a nominal speed.

AutomotiveSimulator.simulate!Method
simulate!(
    scene::Scene{E}, roadway::R, models::Dict{I,M},
    nticks::Int64, timestep::Float64,
    scenes::Vector{Scene{E}}, actions::Union{Nothing, Vector{Scene{A}}} = nothing;
    rng::AbstractRNG = Random.GLOBAL_RNG, callbacks = nothing
) where {E<:Entity,A<:EntityAction,R,I,M<:DriverModel}

Simulate the entities in scene along a roadway for a maximum of nticks time steps of size timestep. Returns the number of successfully performed timesteps.

At each time step, models is used to determine the action for each agent. scenes and actions are pre-allocated vectors of Scenes containing either Entitys (for scenes) or EntityActions (for actions). If actions is equal to nothing (default), the action history is not tracked. scenes must always be provided.

callbacks is an array of callback functions which are invoked before the simulation starts and after every simulation step. Any callback function can cause an early termination by returning true (the default return value for callback functions should be false). The random number generator for the simulation can be provided using the rng keyword argument, it defaults to Random.GLOBAL_RNG.

AutomotiveSimulator.simulateMethod
simulate(
    scene::Scene{E}, roadway::R, models::Dict{I,M}, nticks::Int64, timestep::Float64;
    rng::AbstractRNG = Random.GLOBAL_RNG, callbacks = nothing
) where {E<:Entity,A,R,I,M<:DriverModel}

Simulate a scene. For detailed information, consult the documentation of simulate!. By default, returns a vector containing one scene per time step.

AutomotiveSimulator.simulate_from_history!Method
simulate_from_history!(model::DriverModel, roadway::Roadway, trajdata::Vector{Scene{E}}, egoid, timestep::Float64, 
                      start::Int, stop::Int, scenes::Vector{Scene{E}};
                      actions::Union{Nothing, Vector{Scene{A}}} = nothing, rng::AbstractRNG = Random.GLOBAL_RNG) where {E<:Entity}

Replay the given trajectory except for the entity egoid which follows the given driver model. The resulting trajectory is stored in scenes, the actions of the ego vehicle are stored in actions.

AutomotiveSimulator.simulate_from_historyMethod
simulate_from_history(model::DriverModel, roadway::Roadway, trajdata::Vector{Scene{E}}, egoid, timestep::Float64, 
                      start::Int = 1, stop::Int = length(trajdata);
                      rng::AbstractRNG = Random.GLOBAL_RNG) where {E<:Entity}

Replay the given trajectory except for the entity egoid which follows the given driver model. See simulate_from_history! if you want to provide a container for the results or log actions.

AutomotiveSimulator.time_to_collisionMethod
time_to_collision(roadway::Roadway, scene::Scene, veh::Entity)

Feature function to extract the time to collision with the front neighbor. Returns missing if there are no front neighbor.

AutomotiveSimulator.to_oriented_bounding_box!Method
to_oriented_bounding_box!(retval::ConvexPolygon, center::VecSE2{Float64}, len::Float64, wid::Float64)
to_oriented_bounding_box!(retval::ConvexPolygon, veh::Entity{S,D,I}, center::VecSE2{Float64} = get_center(veh))

Fills in the vertices of retval according to the rectangle specification: center, length, width

AutomotiveSimulator.turn_rate_fMethod
turn_rate_g(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the turn rate history in the Frenet frame of the entity of id vehid using finite differences on heading in the Frenet frame. The first element is missing.

AutomotiveSimulator.turn_rate_gMethod
turn_rate_g(roadway::Roadway, scenes::Vector{<:Scene}, vehid)

returns the turn rate history in the Frenet frame of the entity of id vehid using finite differences on global heading. The first element is missing.

AutomotiveSimulator.velfsMethod
velfs(roadway::Roadway, veh::Entity)

returns the longitudinal velocity in the Frenet frame

AutomotiveSimulator.velgxMethod
velgx(roadway::Roadway, veh::Entity)

returns the velocity in the x direction of the global frame

AutomotiveSimulator.velgyMethod
velgy(roadway::Roadway, veh::Entity)

returns the velocity in the y direction of the global frame

Base.convertMethod
Base.convert(::Type{AccelDesang}, v::Vector{Float64})

Convert a vector containing the acceleration and desired heading angle into AccelDesang type

Base.convertMethod

Take a vector containing acceleration and desired steering angle and convert to AccelSteeringAngle

Base.convertMethod

Convert an input vector containing desired acceleration and turn rate into the AccelTurnrate type

Base.convertMethod
Base.convert(::Type{Entity{S, VehicleDef, I}}, veh::Entity{S, D, I}) where {S,D<:AbstractAgentDefinition,I}

Converts the definition of an entity

Base.copyto!Method
Base.copyto!(v::Vector{Float64}, a::AccelDesang)

Extract the AccelDesang components into a vector and return the vector

Base.copyto!Method

Extract acceleration and steering angle components from AccelSteeringAngle and return them into a vector

Base.copyto!Method

Return a vector containing the desired acceleration and turn rate

Base.getindexMethod
Base.getindex(roadway::Roadway, segid::Int)

returns the segment associated with id segid

Base.getindexMethod
Base.getindex(roadway::Roadway, tag::LaneTag)

returns the lane identified by the tag LaneTag

Base.getindexMethod
Base.getindex(roadway::Roadway, roadind::RoadIndex)

returns the CurvePt on the roadway associated to roadind

Base.getindexMethod
lane[ind::CurveIndex, roadway::Roadway]

Accessor for lanes based on a CurveIndex. Note that we extend the definition of a CurveIndex, previously ind.i ∈ [1, length(curve)-1], to:

ind.i ∈ [0, length(curve)]

where 1 ≤ ind.i ≤ length(curve)-1 is as before, but if the index is on the section between two lanes, we use:

ind.i = length(curve), ind.t ∈ [0,1] for the region between curve[end] → next
ind.i = 0,             ind.t ∈ [0,1] for the region between prev → curve[1]
Base.lengthMethod
length(def::AbstractAgentDefinition)

return the length of the vehicle

Base.randMethod
rand(model::DriverModel)
rand(rng::AbstractRNG, model::DriverModel)

Samples an action from the model.

Base.readMethod
Base.read(io::IO, ::Type{Roadway})

extract roadway information from a text file and returns a roadway object.

Base.writeMethod
Base.write(io::IO, roadway::Roadway)

write all the roadway information to a text file