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 std::pair< RoadOption, WaypointPtr > carla::traffic_manager::Action |
Definition at line 23 of file LocalizationStage.h.
typedef std::vector< Action > carla::traffic_manager::ActionBuffer |
Definition at line 24 of file LocalizationStage.h.
using carla::traffic_manager::Actor = typedef carla::SharedPtr<cc::Actor> |
Definition at line 26 of file LocalizationUtils.h.
Definition at line 21 of file AtomicActorSet.h.
typedef std::unordered_set< ActorId > carla::traffic_manager::ActorIdSet |
Definition at line 28 of file LocalizationUtils.h.
using carla::traffic_manager::ActorList = typedef carla::SharedPtr<cc::ActorList> |
using carla::traffic_manager::ActorMap = typedef std::unordered_map<ActorId, ActorPtr> |
Definition at line 20 of file AtomicActorSet.h.
using carla::traffic_manager::Box = typedef bg::model::box<Point3D> |
Definition at line 52 of file InMemoryMap.h.
typedef std::deque< SimpleWaypointPtr > carla::traffic_manager::Buffer |
Definition at line 44 of file CollisionStage.h.
typedef std::unordered_map< carla::ActorId, Buffer > carla::traffic_manager::BufferMap |
Definition at line 45 of file CollisionStage.h.
using carla::traffic_manager::CollisionFrame = typedef std::vector<CollisionHazardData> |
Definition at line 49 of file DataStructures.h.
using carla::traffic_manager::CollisionLockMap = typedef std::unordered_map<ActorId, CollisionLock> |
Definition at line 39 of file CollisionStage.h.
using carla::traffic_manager::ControlFrame = typedef std::vector<carla::rpc::Command> |
Definition at line 51 of file DataStructures.h.
using carla::traffic_manager::GeodesicBoundaryMap = typedef std::unordered_map<ActorId, LocationVector> |
Definition at line 47 of file CollisionStage.h.
Definition at line 48 of file InMemoryMap.h.
using carla::traffic_manager::GeometryComparisonMap = typedef std::unordered_map<uint64_t, GeometryComparison> |
Definition at line 48 of file CollisionStage.h.
using carla::traffic_manager::IdleTimeMap = typedef std::unordered_map<ActorId, double> |
using carla::traffic_manager::Junction = typedef carla::SharedPtr<carla::client::Junction> |
Definition at line 30 of file DataStructures.h.
using carla::traffic_manager::JunctionID = typedef carla::road::JuncId |
Definition at line 29 of file DataStructures.h.
using carla::traffic_manager::KinematicStateMap = typedef std::unordered_map<ActorId, KinematicState> |
Definition at line 26 of file SimulationState.h.
using carla::traffic_manager::LaneChangeSWptMap = typedef std::unordered_map<ActorId, SimpleWaypointPtr> |
Definition at line 21 of file LocalizationStage.h.
using carla::traffic_manager::LocalizationFrame = typedef std::vector<LocalizationData> |
Definition at line 42 of file DataStructures.h.
typedef std::shared_ptr< InMemoryMap > carla::traffic_manager::LocalMapPtr |
using carla::traffic_manager::LocationVector = typedef std::vector<cg::Location> |
Definition at line 46 of file CollisionStage.h.
using carla::traffic_manager::NodeList = typedef std::vector<SimpleWaypointPtr> |
Definition at line 47 of file InMemoryMap.h.
typedef std::vector< cg::Location > carla::traffic_manager::Path |
Definition at line 25 of file LocalizationStage.h.
using carla::traffic_manager::Point2D = typedef bg::model::point<double, 2, bg::cs::cartesian> |
Definition at line 12 of file CollisionStage.cpp.
using carla::traffic_manager::Point3D = typedef bg::model::point<float, 3, bg::cs::cartesian> |
Definition at line 51 of file InMemoryMap.h.
using carla::traffic_manager::Polygon = typedef bg::model::polygon<bg::model::d2::point_xy<double> > |
Definition at line 49 of file CollisionStage.h.
using carla::traffic_manager::RawNodeList = typedef std::vector<WaypointPtr> |
Definition at line 20 of file InMemoryMap.cpp.
typedef std::vector< uint8_t > carla::traffic_manager::Route |
Definition at line 26 of file LocalizationStage.h.
using carla::traffic_manager::Rtree = typedef bgi::rtree<SpatialTreeEntry, bgi::rstar<16> > |
Definition at line 58 of file InMemoryMap.h.
using carla::traffic_manager::SegmentId = typedef std::tuple<crd::RoadId, crd::LaneId, crd::SectionId> |
Definition at line 55 of file InMemoryMap.h.
using carla::traffic_manager::SegmentMap = typedef std::map<SegmentId, std::vector<SimpleWaypointPtr> > |
Definition at line 57 of file InMemoryMap.h.
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.
typedef std::shared_ptr< SimpleWaypoint > carla::traffic_manager::SimpleWaypointPtr |
Definition at line 12 of file CachedSimpleWaypoint.cpp.
using carla::traffic_manager::SpatialTreeEntry = typedef std::pair<Point3D, SimpleWaypointPtr> |
Definition at line 53 of file InMemoryMap.h.
using carla::traffic_manager::StaticAttributeMap = typedef std::unordered_map<ActorId, StaticAttributes> |
Definition at line 40 of file SimulationState.h.
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.
typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimeInstance |
Definition at line 34 of file DataStructures.h.
typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimePoint |
Definition at line 18 of file SnippetProfiler.h.
using carla::traffic_manager::TLFrame = typedef std::vector<bool> |
Definition at line 53 of file DataStructures.h.
using carla::traffic_manager::TLGroup = typedef std::vector<carla::SharedPtr<carla::client::TrafficLight> > |
Definition at line 44 of file TrafficManagerLocal.h.
using carla::traffic_manager::TLMap = typedef std::unordered_map<std::string, SharedPtr<client::Actor> > |
Definition at line 20 of file MotionPlanStage.h.
Definition at line 13 of file CollisionStage.cpp.
using carla::traffic_manager::TopologyList = typedef std::vector<std::pair<WaypointPtr, WaypointPtr> > |
Definition at line 19 of file InMemoryMap.cpp.
using carla::traffic_manager::TrafficLightStateMap = typedef std::unordered_map<ActorId, TrafficLightState> |
Definition at line 32 of file SimulationState.h.
Definition at line 45 of file InMemoryMap.h.
using carla::traffic_manager::WorldMap = typedef carla::SharedPtr<const cc::Map> |
Definition at line 49 of file InMemoryMap.h.
Enumerator | |
---|---|
Vehicle | |
Pedestrian | |
Any |
Definition at line 11 of file SimulationState.h.
|
strong |
Enumerator | |
---|---|
Void | |
Left | |
Right | |
Straight | |
LaneFollow | |
ChangeLaneLeft | |
ChangeLaneRight | |
RoadEnd |
Definition at line 25 of file SimpleWaypoint.h.
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().
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().
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().
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().
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().