CARLA
Namespaces | Classes | Typedefs | Enumerations | Functions
carla::traffic_manager Namespace Reference

Namespaces

 constants
 
 PID
 

Classes

struct  ActuationSignal
 Structure to hold the actuation signals. More...
 
class  ALSM
 ALSM: Agent Lifecycle and State Managerment This class has functionality to update the local cache of kinematic states and manage memory and cleanup for varying number of vehicles in the simulation. More...
 
class  AtomicActorSet
 
class  AtomicMap
 
class  CachedSimpleWaypoint
 
struct  ChangeLaneInfo
 
struct  CollisionHazardData
 
struct  CollisionLock
 
class  CollisionStage
 This class has functionality to detect potential collision with a nearby actor. More...
 
struct  GeometryComparison
 
class  InMemoryMap
 This class builds a discretized local map-cache. More...
 
struct  KinematicState
 
struct  LocalizationData
 
class  LocalizationStage
 This class has functionality to maintain a horizon of waypoints ahead of the vehicle for it to follow. More...
 
class  MotionPlanStage
 
class  Parameters
 
class  RandomGenerator
 
class  SimpleWaypoint
 This is a simple wrapper class on Carla's waypoint object. More...
 
class  SimulationState
 This class holds the state of all the vehicles in the simlation. More...
 
class  SnippetProfiler
 
class  Stage
 Stage type interface. More...
 
struct  StateEntry
 Structure to hold the controller state. More...
 
struct  StaticAttributes
 
class  TrackTraffic
 
class  TrafficLightStage
 This class has functionality for responding to traffic lights and managing entry into non-signalized junctions. More...
 
struct  TrafficLightState
 
class  TrafficManager
 This class integrates all the various stages of the traffic manager appropriately using messengers. More...
 
class  TrafficManagerBase
 The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. More...
 
class  TrafficManagerClient
 Provides communication with the rpc of TrafficManagerServer. More...
 
class  TrafficManagerLocal
 The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. More...
 
class  TrafficManagerRemote
 The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. More...
 
class  TrafficManagerServer
 
class  VehicleLightStage
 This class has functionality for turning on/off the vehicle lights according to the current vehicle state and its surrounding environment. More...
 

Typedefs

using Action = std::pair< RoadOption, WaypointPtr >
 
using ActionBuffer = std::vector< Action >
 
using Actor = carla::SharedPtr< cc::Actor >
 
using ActorId = carla::ActorId
 
using ActorIdSet = std::unordered_set< ActorId >
 
using ActorList = carla::SharedPtr< cc::ActorList >
 
using ActorMap = std::unordered_map< ActorId, ActorPtr >
 
using ActorPtr = carla::SharedPtr< cc::Actor >
 
using Box = bg::model::box< Point3D >
 
using Buffer = std::deque< std::shared_ptr< SimpleWaypoint > >
 
using BufferMap = std::unordered_map< carla::ActorId, Buffer >
 
using CollisionFrame = std::vector< CollisionHazardData >
 
using CollisionLockMap = std::unordered_map< ActorId, CollisionLock >
 
using ControlFrame = std::vector< carla::rpc::Command >
 
using GeodesicBoundaryMap = std::unordered_map< ActorId, LocationVector >
 
using GeoGridId = crd::JuncId
 
using GeometryComparisonMap = std::unordered_map< uint64_t, GeometryComparison >
 
using IdleTimeMap = std::unordered_map< ActorId, double >
 
using Junction = carla::SharedPtr< carla::client::Junction >
 
using JunctionID = carla::road::JuncId
 
using KinematicStateMap = std::unordered_map< ActorId, KinematicState >
 
using LaneChangeSWptMap = std::unordered_map< ActorId, SimpleWaypointPtr >
 
using LocalizationFrame = std::vector< LocalizationData >
 
using LocalMapPtr = std::shared_ptr< InMemoryMap >
 
using LocationVector = std::vector< cg::Location >
 
using NodeList = std::vector< SimpleWaypointPtr >
 
using Path = std::vector< cg::Location >
 
using Point2D = bg::model::point< double, 2, bg::cs::cartesian >
 
using Point3D = bg::model::point< float, 3, bg::cs::cartesian >
 
using Polygon = bg::model::polygon< bg::model::d2::point_xy< double > >
 
using RawNodeList = std::vector< WaypointPtr >
 
using Route = std::vector< uint8_t >
 
using Rtree = bgi::rtree< SpatialTreeEntry, bgi::rstar< 16 > >
 
using SegmentId = std::tuple< crd::RoadId, crd::LaneId, crd::SectionId >
 
using SegmentMap = std::map< SegmentId, std::vector< SimpleWaypointPtr > >
 
using SegmentTopology = std::map< SegmentId, std::pair< std::vector< SegmentId >, std::vector< SegmentId > >>
 
using SimpleWaypointPtr = std::shared_ptr< SimpleWaypoint >
 
using SpatialTreeEntry = std::pair< Point3D, SimpleWaypointPtr >
 
using StaticAttributeMap = std::unordered_map< ActorId, StaticAttributes >
 
using TargetWPInfo = std::pair< SimpleWaypointPtr, uint64_t >
 Method to return the wayPoints from the waypoint Buffer by using target point distance. More...
 
using TimeInstance = chr::time_point< chr::system_clock, chr::nanoseconds >
 
using TimePoint = chr::time_point< chr::system_clock, chr::nanoseconds >
 
using TLFrame = std::vector< bool >
 
using TLGroup = std::vector< carla::SharedPtr< carla::client::TrafficLight > >
 
using TLMap = std::unordered_map< std::string, SharedPtr< client::Actor > >
 
using TLS = carla::rpc::TrafficLightState
 
using TopologyList = std::vector< std::pair< WaypointPtr, WaypointPtr > >
 
using TrafficLightStateMap = std::unordered_map< ActorId, TrafficLightState >
 
using WaypointPtr = carla::SharedPtr< cc::Waypoint >
 
using WorldMap = carla::SharedPtr< const cc::Map >
 

Enumerations

enum  ActorType { Vehicle, Pedestrian, Any }
 
enum  RoadOption : uint8_t {
  RoadOption::Void = 0, RoadOption::Left = 1, RoadOption::Right = 2, RoadOption::Straight = 3,
  RoadOption::LaneFollow = 4, RoadOption::ChangeLaneLeft = 5, RoadOption::ChangeLaneRight = 6, RoadOption::RoadEnd = 7
}
 

Functions

float DeviationCrossProduct (const cg::Location &reference_location, const cg::Vector3D &heading_vector, const cg::Location &target_location)
 Returns the cross product (z component value) between the vehicle's heading vector and the vector along the direction to the next target waypoint on the horizon. More...
 
float DeviationDotProduct (const cg::Location &reference_location, const cg::Vector3D &heading_vector, const cg::Location &target_location)
 Returns the dot product between the vehicle's heading vector and the vector along the direction to the next target waypoint on the horizon. More...
 
TargetWPInfo GetTargetWaypoint (const Buffer &waypoint_buffer, const float &target_point_distance)
 
void PopWaypoint (ActorId actor_id, TrackTraffic &track_traffic, Buffer &buffer, bool front_or_back)
 
void PushWaypoint (ActorId actor_id, TrackTraffic &track_traffic, Buffer &buffer, SimpleWaypointPtr &waypoint)
 

Typedef Documentation

◆ Action

Definition at line 23 of file LocalizationStage.h.

◆ ActionBuffer

Definition at line 24 of file LocalizationStage.h.

◆ Actor

Definition at line 26 of file LocalizationUtils.h.

◆ ActorId

Definition at line 21 of file AtomicActorSet.h.

◆ ActorIdSet

typedef std::unordered_set< ActorId > carla::traffic_manager::ActorIdSet

Definition at line 28 of file LocalizationUtils.h.

◆ ActorList

Definition at line 33 of file ALSM.h.

◆ ActorMap

using carla::traffic_manager::ActorMap = typedef std::unordered_map<ActorId, ActorPtr>

Definition at line 34 of file ALSM.h.

◆ ActorPtr

Definition at line 20 of file AtomicActorSet.h.

◆ Box

using carla::traffic_manager::Box = typedef bg::model::box<Point3D>

Definition at line 52 of file InMemoryMap.h.

◆ Buffer

Definition at line 44 of file CollisionStage.h.

◆ BufferMap

Definition at line 45 of file CollisionStage.h.

◆ CollisionFrame

Definition at line 49 of file DataStructures.h.

◆ CollisionLockMap

using carla::traffic_manager::CollisionLockMap = typedef std::unordered_map<ActorId, CollisionLock>

Definition at line 39 of file CollisionStage.h.

◆ ControlFrame

Definition at line 51 of file DataStructures.h.

◆ GeodesicBoundaryMap

Definition at line 47 of file CollisionStage.h.

◆ GeoGridId

Definition at line 48 of file InMemoryMap.h.

◆ GeometryComparisonMap

using carla::traffic_manager::GeometryComparisonMap = typedef std::unordered_map<uint64_t, GeometryComparison>

Definition at line 48 of file CollisionStage.h.

◆ IdleTimeMap

using carla::traffic_manager::IdleTimeMap = typedef std::unordered_map<ActorId, double>

Definition at line 35 of file ALSM.h.

◆ Junction

Definition at line 30 of file DataStructures.h.

◆ JunctionID

Definition at line 29 of file DataStructures.h.

◆ KinematicStateMap

Definition at line 26 of file SimulationState.h.

◆ LaneChangeSWptMap

Definition at line 21 of file LocalizationStage.h.

◆ LocalizationFrame

Definition at line 42 of file DataStructures.h.

◆ LocalMapPtr

Definition at line 36 of file ALSM.h.

◆ LocationVector

Definition at line 46 of file CollisionStage.h.

◆ NodeList

Definition at line 47 of file InMemoryMap.h.

◆ Path

Definition at line 25 of file LocalizationStage.h.

◆ Point2D

using carla::traffic_manager::Point2D = typedef bg::model::point<double, 2, bg::cs::cartesian>

Definition at line 12 of file CollisionStage.cpp.

◆ Point3D

using carla::traffic_manager::Point3D = typedef bg::model::point<float, 3, bg::cs::cartesian>

Definition at line 51 of file InMemoryMap.h.

◆ Polygon

using carla::traffic_manager::Polygon = typedef bg::model::polygon<bg::model::d2::point_xy<double> >

Definition at line 49 of file CollisionStage.h.

◆ RawNodeList

using carla::traffic_manager::RawNodeList = typedef std::vector<WaypointPtr>

Definition at line 20 of file InMemoryMap.cpp.

◆ Route

typedef std::vector< uint8_t > carla::traffic_manager::Route

Definition at line 26 of file LocalizationStage.h.

◆ Rtree

using carla::traffic_manager::Rtree = typedef bgi::rtree<SpatialTreeEntry, bgi::rstar<16> >

Definition at line 58 of file InMemoryMap.h.

◆ SegmentId

Definition at line 55 of file InMemoryMap.h.

◆ SegmentMap

using carla::traffic_manager::SegmentMap = typedef std::map<SegmentId, std::vector<SimpleWaypointPtr> >

Definition at line 57 of file InMemoryMap.h.

◆ SegmentTopology

using carla::traffic_manager::SegmentTopology = typedef std::map<SegmentId, std::pair<std::vector<SegmentId>, std::vector<SegmentId> >>

Definition at line 56 of file InMemoryMap.h.

◆ SimpleWaypointPtr

Definition at line 12 of file CachedSimpleWaypoint.cpp.

◆ SpatialTreeEntry

Definition at line 53 of file InMemoryMap.h.

◆ StaticAttributeMap

Definition at line 40 of file SimulationState.h.

◆ TargetWPInfo

using carla::traffic_manager::TargetWPInfo = typedef std::pair<SimpleWaypointPtr,uint64_t>

Method to return the wayPoints from the waypoint Buffer by using target point distance.

Definition at line 56 of file LocalizationUtils.h.

◆ TimeInstance

typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimeInstance

Definition at line 34 of file DataStructures.h.

◆ TimePoint

typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimePoint

Definition at line 18 of file SnippetProfiler.h.

◆ TLFrame

using carla::traffic_manager::TLFrame = typedef std::vector<bool>

Definition at line 53 of file DataStructures.h.

◆ TLGroup

Definition at line 44 of file TrafficManagerLocal.h.

◆ TLMap

using carla::traffic_manager::TLMap = typedef std::unordered_map<std::string, SharedPtr<client::Actor> >

Definition at line 20 of file MotionPlanStage.h.

◆ TLS

Definition at line 13 of file CollisionStage.cpp.

◆ TopologyList

using carla::traffic_manager::TopologyList = typedef std::vector<std::pair<WaypointPtr, WaypointPtr> >

Definition at line 19 of file InMemoryMap.cpp.

◆ TrafficLightStateMap

Definition at line 32 of file SimulationState.h.

◆ WaypointPtr

Definition at line 45 of file InMemoryMap.h.

◆ WorldMap

Definition at line 49 of file InMemoryMap.h.

Enumeration Type Documentation

◆ ActorType

Enumerator
Vehicle 
Pedestrian 
Any 

Definition at line 11 of file SimulationState.h.

◆ RoadOption

enum carla::traffic_manager::RoadOption : uint8_t
strong
Enumerator
Void 
Left 
Right 
Straight 
LaneFollow 
ChangeLaneLeft 
ChangeLaneRight 
RoadEnd 

Definition at line 25 of file SimpleWaypoint.h.

Function Documentation

◆ DeviationCrossProduct()

float carla::traffic_manager::DeviationCrossProduct ( const cg::Location reference_location,
const cg::Vector3D heading_vector,
const cg::Location target_location 
)

Returns the cross product (z component value) between the vehicle's heading vector and the vector along the direction to the next target waypoint on the horizon.

Definition at line 16 of file LocalizationUtils.cpp.

References carla::road::EPSILON, carla::geom::Vector3D::MakeSafeUnitVector(), carla::geom::Vector3D::x, and carla::geom::Vector3D::y.

Referenced by carla::traffic_manager::MotionPlanStage::Update().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ DeviationDotProduct()

float carla::traffic_manager::DeviationDotProduct ( const cg::Location reference_location,
const cg::Vector3D heading_vector,
const cg::Location target_location 
)

Returns the dot product between the vehicle's heading vector and the vector along the direction to the next target waypoint on the horizon.

Definition at line 25 of file LocalizationUtils.cpp.

References carla::geom::Math::Dot(), carla::road::EPSILON, carla::geom::Vector3D::MakeSafeUnitVector(), min(), carla::geom::Vector3D::x, carla::geom::Vector3D::y, and carla::geom::Vector3D::z.

Referenced by carla::traffic_manager::LocalizationStage::Update(), and carla::traffic_manager::MotionPlanStage::Update().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ GetTargetWaypoint()

TargetWPInfo carla::traffic_manager::GetTargetWaypoint ( const Buffer waypoint_buffer,
const float &  target_point_distance 
)

Condition to determine forward or backward scanning of waypoint buffer.

Definition at line 59 of file LocalizationUtils.cpp.

References carla::traffic_manager::constants::Map::INV_MAP_RESOLUTION.

Referenced by carla::traffic_manager::TrafficLightStage::GetAffectedJunctionId(), carla::traffic_manager::CollisionStage::GetGeodesicBoundary(), carla::traffic_manager::LocalizationStage::Update(), carla::traffic_manager::MotionPlanStage::Update(), and carla::traffic_manager::CollisionStage::Update().

+ Here is the caller graph for this function:

◆ PopWaypoint()

void carla::traffic_manager::PopWaypoint ( ActorId  actor_id,
TrackTraffic track_traffic,
Buffer buffer,
bool  front_or_back 
)

Definition at line 46 of file LocalizationUtils.cpp.

References carla::traffic_manager::TrackTraffic::RemovePassingVehicle().

Referenced by carla::traffic_manager::LocalizationStage::ImportPath(), carla::traffic_manager::LocalizationStage::ImportRoute(), and carla::traffic_manager::LocalizationStage::Update().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ PushWaypoint()

void carla::traffic_manager::PushWaypoint ( ActorId  actor_id,
TrackTraffic track_traffic,
Buffer buffer,
SimpleWaypointPtr waypoint 
)

Definition at line 38 of file LocalizationUtils.cpp.

References carla::traffic_manager::TrackTraffic::UpdatePassingVehicle().

Referenced by carla::traffic_manager::LocalizationStage::ExtendAndFindSafeSpace(), carla::traffic_manager::LocalizationStage::ImportPath(), carla::traffic_manager::LocalizationStage::ImportRoute(), and carla::traffic_manager::LocalizationStage::Update().

+ Here is the call graph for this function:
+ Here is the caller graph for this function: