命名空间 | |
namespace | constants |
namespace | PID |
类 | |
struct | ActuationSignal |
Structure to hold the actuation signals. 更多... | |
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. 更多... | |
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. 更多... | |
struct | GeometryComparison |
class | InMemoryMap |
This class builds a discretized local map-cache. 更多... | |
struct | KinematicState |
struct | LocalizationData |
class | LocalizationStage |
This class has functionality to maintain a horizon of waypoints ahead of the vehicle for it to follow. 更多... | |
class | MotionPlanStage |
class | Parameters |
class | RandomGenerator |
class | SimpleWaypoint |
This is a simple wrapper class on Carla's waypoint object. 更多... | |
class | SimulationState |
This class holds the state of all the vehicles in the simlation. 更多... | |
class | SnippetProfiler |
class | Stage |
Stage type interface. 更多... | |
struct | StateEntry |
Structure to hold the controller state. 更多... | |
struct | StaticAttributes |
class | TrackTraffic |
class | TrafficLightStage |
This class has functionality for responding to traffic lights and managing entry into non-signalized junctions. 更多... | |
struct | TrafficLightState |
class | TrafficManager |
This class integrates all the various stages of the traffic manager appropriately using messengers. 更多... | |
class | TrafficManagerBase |
The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. 更多... | |
class | TrafficManagerClient |
Provides communication with the rpc of TrafficManagerServer. 更多... | |
class | TrafficManagerLocal |
The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. 更多... | |
class | TrafficManagerRemote |
The function of this class is to integrate all the various stages of the traffic manager appropriately using messengers. 更多... | |
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. 更多... | |
类型定义 | |
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 | |
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> |
枚举 | |
enum | ActorType { Vehicle , Pedestrian , Any } |
enum class | RoadOption : uint8_t { Void = 0 , Left = 1 , Right = 2 , Straight = 3 , LaneFollow = 4 , ChangeLaneLeft = 5 , ChangeLaneRight = 6 , RoadEnd = 7 } |
函数 | |
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. | |
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. | |
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 = std::pair<RoadOption, WaypointPtr> |
在文件 LocalizationStage.h 第 23 行定义.
typedef std::vector< Action > carla::traffic_manager::ActionBuffer = std::vector<Action> |
在文件 LocalizationStage.h 第 24 行定义.
在文件 LocalizationUtils.h 第 26 行定义.
在文件 AtomicActorSet.h 第 21 行定义.
typedef std::unordered_set< ActorId > carla::traffic_manager::ActorIdSet = std::unordered_set<ActorId> |
在文件 LocalizationUtils.h 第 28 行定义.
using carla::traffic_manager::ActorMap = std::unordered_map<ActorId, ActorPtr> |
typedef carla::SharedPtr< carla::client::Actor > carla::traffic_manager::ActorPtr = carla::SharedPtr<cc::Actor> |
在文件 AtomicActorSet.h 第 20 行定义.
using carla::traffic_manager::Box = bg::model::box<Point3D> |
在文件 InMemoryMap.h 第 52 行定义.
typedef std::deque< SimpleWaypointPtr > carla::traffic_manager::Buffer = std::deque<std::shared_ptr<SimpleWaypoint>> |
在文件 CollisionStage.h 第 44 行定义.
typedef std::unordered_map< carla::ActorId, Buffer > carla::traffic_manager::BufferMap = std::unordered_map<carla::ActorId, Buffer> |
在文件 CollisionStage.h 第 45 行定义.
using carla::traffic_manager::CollisionFrame = std::vector<CollisionHazardData> |
在文件 DataStructures.h 第 49 行定义.
using carla::traffic_manager::CollisionLockMap = std::unordered_map<ActorId, CollisionLock> |
在文件 CollisionStage.h 第 39 行定义.
using carla::traffic_manager::ControlFrame = std::vector<carla::rpc::Command> |
在文件 DataStructures.h 第 51 行定义.
using carla::traffic_manager::GeodesicBoundaryMap = std::unordered_map<ActorId, LocationVector> |
在文件 CollisionStage.h 第 47 行定义.
在文件 InMemoryMap.h 第 48 行定义.
using carla::traffic_manager::GeometryComparisonMap = std::unordered_map<uint64_t, GeometryComparison> |
在文件 CollisionStage.h 第 48 行定义.
using carla::traffic_manager::IdleTimeMap = std::unordered_map<ActorId, double> |
在文件 DataStructures.h 第 30 行定义.
在文件 DataStructures.h 第 29 行定义.
using carla::traffic_manager::KinematicStateMap = std::unordered_map<ActorId, KinematicState> |
在文件 SimulationState.h 第 26 行定义.
using carla::traffic_manager::LaneChangeSWptMap = std::unordered_map<ActorId, SimpleWaypointPtr> |
在文件 LocalizationStage.h 第 21 行定义.
using carla::traffic_manager::LocalizationFrame = std::vector<LocalizationData> |
在文件 DataStructures.h 第 42 行定义.
typedef std::shared_ptr< InMemoryMap > carla::traffic_manager::LocalMapPtr = std::shared_ptr<InMemoryMap> |
using carla::traffic_manager::LocationVector = std::vector<cg::Location> |
在文件 CollisionStage.h 第 46 行定义.
using carla::traffic_manager::NodeList = std::vector<SimpleWaypointPtr> |
在文件 InMemoryMap.h 第 47 行定义.
typedef std::vector< cg::Location > carla::traffic_manager::Path = std::vector<cg::Location> |
在文件 LocalizationStage.h 第 25 行定义.
using carla::traffic_manager::Point2D = bg::model::point<double, 2, bg::cs::cartesian> |
在文件 CollisionStage.cpp 第 12 行定义.
using carla::traffic_manager::Point3D = bg::model::point<float, 3, bg::cs::cartesian> |
在文件 InMemoryMap.h 第 51 行定义.
using carla::traffic_manager::Polygon = bg::model::polygon<bg::model::d2::point_xy<double>> |
在文件 CollisionStage.h 第 49 行定义.
using carla::traffic_manager::RawNodeList = std::vector<WaypointPtr> |
在文件 InMemoryMap.cpp 第 20 行定义.
typedef std::vector< uint8_t > carla::traffic_manager::Route = std::vector<uint8_t> |
在文件 LocalizationStage.h 第 26 行定义.
using carla::traffic_manager::Rtree = bgi::rtree<SpatialTreeEntry, bgi::rstar<16>> |
在文件 InMemoryMap.h 第 58 行定义.
using carla::traffic_manager::SegmentId = std::tuple<crd::RoadId, crd::LaneId, crd::SectionId> |
在文件 InMemoryMap.h 第 55 行定义.
using carla::traffic_manager::SegmentMap = std::map<SegmentId, std::vector<SimpleWaypointPtr>> |
在文件 InMemoryMap.h 第 57 行定义.
using carla::traffic_manager::SegmentTopology = std::map<SegmentId, std::pair<std::vector<SegmentId>, std::vector<SegmentId>>> |
在文件 InMemoryMap.h 第 56 行定义.
typedef std::shared_ptr< SimpleWaypoint > carla::traffic_manager::SimpleWaypointPtr = std::shared_ptr<SimpleWaypoint> |
在文件 CachedSimpleWaypoint.cpp 第 12 行定义.
using carla::traffic_manager::SpatialTreeEntry = std::pair<Point3D, SimpleWaypointPtr> |
在文件 InMemoryMap.h 第 53 行定义.
using carla::traffic_manager::StaticAttributeMap = std::unordered_map<ActorId, StaticAttributes> |
在文件 SimulationState.h 第 40 行定义.
using carla::traffic_manager::TargetWPInfo = std::pair<SimpleWaypointPtr,uint64_t> |
Method to return the wayPoints from the waypoint Buffer by using target point distance
在文件 LocalizationUtils.h 第 56 行定义.
typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimeInstance = chr::time_point<chr::system_clock, chr::nanoseconds> |
在文件 DataStructures.h 第 34 行定义.
typedef chr::time_point< chr::system_clock, chr::nanoseconds > carla::traffic_manager::TimePoint = chr::time_point<chr::system_clock, chr::nanoseconds> |
在文件 SnippetProfiler.h 第 18 行定义.
using carla::traffic_manager::TLFrame = std::vector<bool> |
在文件 DataStructures.h 第 53 行定义.
using carla::traffic_manager::TLGroup = std::vector<carla::SharedPtr<carla::client::TrafficLight>> |
在文件 TrafficManagerLocal.h 第 44 行定义.
using carla::traffic_manager::TLMap = std::unordered_map<std::string, SharedPtr<client::Actor>> |
在文件 MotionPlanStage.h 第 20 行定义.
在文件 CollisionStage.cpp 第 13 行定义.
using carla::traffic_manager::TopologyList = std::vector<std::pair<WaypointPtr, WaypointPtr>> |
在文件 InMemoryMap.cpp 第 19 行定义.
using carla::traffic_manager::TrafficLightStateMap = std::unordered_map<ActorId, TrafficLightState> |
在文件 SimulationState.h 第 32 行定义.
typedef carla::SharedPtr< carla::client::Waypoint > carla::traffic_manager::WaypointPtr = carla::SharedPtr<cc::Waypoint> |
在文件 InMemoryMap.h 第 45 行定义.
using carla::traffic_manager::WorldMap = carla::SharedPtr<const cc::Map> |
在文件 InMemoryMap.h 第 49 行定义.
枚举值 | |
---|---|
Vehicle | |
Pedestrian | |
Any |
在文件 SimulationState.h 第 11 行定义.
|
strong |
枚举值 | |
---|---|
Void | |
Left | |
Right | |
Straight | |
LaneFollow | |
ChangeLaneLeft | |
ChangeLaneRight | |
RoadEnd |
在文件 SimpleWaypoint.h 第 25 行定义.
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.
在文件 LocalizationUtils.cpp 第 16 行定义.
引用了 carla::geom::Vector3D::MakeSafeUnitVector(), carla::geom::Vector3D::x , 以及 carla::geom::Vector3D::y.
被这些函数引用 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.
在文件 LocalizationUtils.cpp 第 25 行定义.
引用了 carla::geom::Vector3D::MakeSafeUnitVector(), carla::geom::Vector3D::x, carla::geom::Vector3D::y , 以及 carla::geom::Vector3D::z.
被这些函数引用 carla::traffic_manager::MotionPlanStage::Update() , 以及 carla::traffic_manager::LocalizationStage::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.
在文件 LocalizationUtils.cpp 第 59 行定义.
被这些函数引用 carla::traffic_manager::TrafficLightStage::GetAffectedJunctionId(), carla::traffic_manager::CollisionStage::GetGeodesicBoundary(), carla::traffic_manager::MotionPlanStage::Update(), carla::traffic_manager::CollisionStage::Update() , 以及 carla::traffic_manager::LocalizationStage::Update().
void carla::traffic_manager::PopWaypoint | ( | ActorId | actor_id, |
TrackTraffic & | track_traffic, | ||
Buffer & | buffer, | ||
bool | front_or_back ) |
在文件 LocalizationUtils.cpp 第 46 行定义.
引用了 carla::traffic_manager::TrackTraffic::RemovePassingVehicle().
被这些函数引用 carla::traffic_manager::LocalizationStage::ImportPath(), carla::traffic_manager::LocalizationStage::ImportRoute() , 以及 carla::traffic_manager::LocalizationStage::Update().
void carla::traffic_manager::PushWaypoint | ( | ActorId | actor_id, |
TrackTraffic & | track_traffic, | ||
Buffer & | buffer, | ||
SimpleWaypointPtr & | waypoint ) |
在文件 LocalizationUtils.cpp 第 38 行定义.
引用了 carla::traffic_manager::TrackTraffic::UpdatePassingVehicle().
被这些函数引用 carla::traffic_manager::LocalizationStage::ExtendAndFindSafeSpace(), carla::traffic_manager::LocalizationStage::ImportPath(), carla::traffic_manager::LocalizationStage::ImportRoute() , 以及 carla::traffic_manager::LocalizationStage::Update().