Apollo  6.0
Open source self driving car software
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
apollo::planning Namespace Reference

apollo::planning More...

Namespaces

 scenario
 
 util
 

Classes

class  AffineConstraint
 
struct  AnchorPoint
 
class  AutotuningBaseModel
 
class  AutotuningFeatureBuilder
 : build model related input feature from raw feature generator More...
 
class  AutotuningMLPModel
 
class  AutotuningRawFeatureGenerator
 
class  AutotuningSpeedFeatureBuilder
 : build the mlp cost functional for speed profile based on trajectory raw feature More...
 
class  AutotuningSpeedMLPModel
 
class  BacksideVehicle
 
class  BackupTrajectoryGenerator
 
class  BirdviewImgFeatureRenderer
 
class  CollisionChecker
 
class  ComparableCost
 
class  ConstantDecelerationTrajectory1d
 
class  ConstantJerkTrajectory1d
 
class  ConstraintChecker
 
class  ConstraintChecker1d
 
class  CosThetaIpoptInterface
 
class  CosThetaSmoother
 
class  CreepDecider
 
class  Crosswalk
 
class  CubicPolynomialCurve1d
 
class  Curve1d
 
class  CurveMath
 
class  Decider
 
class  DecisionData
 
class  DependencyInjector
 
class  Destination
 
class  DiscretePointsMath
 
class  DiscretePointsReferenceLineSmoother
 
class  DiscretizedPath
 
class  DiscretizedTrajectory
 
class  DistanceApproachInterface
 
class  DistanceApproachIPOPTCUDAInterface
 
class  DistanceApproachIPOPTFixedDualInterface
 
class  DistanceApproachIPOPTFixedTsInterface
 
class  DistanceApproachIPOPTInterface
 
class  DistanceApproachIPOPTRelaxEndInterface
 
class  DistanceApproachIPOPTRelaxEndSlackInterface
 
class  DistanceApproachProblem
 
class  DpRoadGraph
 
class  DpStCost
 
class  DualVariableWarmStartIPOPTInterface
 
class  DualVariableWarmStartIPOPTQPInterface
 
class  DualVariableWarmStartOSQPInterface
 
class  DualVariableWarmStartProblem
 
class  DualVariableWarmStartSlackOSQPInterface
 
class  EgoInfo
 
class  EndConditionSampler
 
struct  EnumClassHash
 
class  Evaluator
 
class  EvaluatorLogger
 
class  FeasibleRegion
 
class  FeatureOutput
 
class  FemPosDeviationIpoptInterface
 
class  FemPosDeviationOsqpInterface
 
class  FemPosDeviationSmoother
 
class  FemPosDeviationSqpOsqpInterface
 
class  Frame
 Frame holds all data for one planning cycle. More...
 
class  FrameHistory
 
class  FrenetFramePath
 
struct  GearSwitchStates
 
struct  GridAStartResult
 
class  GriddedPathTimeGraph
 
class  GridSearch
 
class  History
 
class  HistoryFrame
 
class  HistoryObjectDecision
 
class  HistoryObjectStatus
 
class  HistoryStatus
 
class  HybridAStar
 
struct  HybridAStartResult
 
class  IndexedList
 
class  IndexedQueue
 
class  IterativeAnchoringSmoother
 
class  KeepClear
 
class  LaneChangeDecider
 
class  LateralOSQPOptimizer
 
class  LateralQPOptimizer
 
class  LatticePlanner
 
class  LatticeTrajectory1d
 
class  LearningBasedData
 
class  LearningModelInferenceTask
 
class  LearningModelInferenceTrajectoryTask
 
struct  LocalView
 
class  MessageProcess
 
class  ModelInference
 
class  NaviObstacleDecider
 NaviObstacleDecider is used to make appropriate decisions for obstacles around the vehicle in navigation mode. Note that NaviObstacleDecider is only used in navigation mode (turn on navigation mode by setting "FLAGS_use_navigation_mode" to "true") and do not use it in standard mode. More...
 
class  NaviPathDecider
 NaviPathDecider is used to generate the local driving path of the .* vehicle in navigation mode. Note that NaviPathDecider is only used in navigation mode (turn on navigation mode by setting "FLAGS_use_navigation_mode" to "true") and do not use it in standard mode. More...
 
class  NaviPlanner
 NaviPlanner is a planner based on real-time relative maps. It uses the vehicle's FLU (Front-Left-Up) coordinate system to accomplish tasks such as cruising, following, overtaking, nudging, changing lanes and stopping. Note that NaviPlanner is only used in navigation mode (turn on navigation mode by setting "FLAGS_use_navigation_mode" to "true") and do not use it in standard mode. More...
 
class  NaviPlannerDispatcher
 
class  NaviPlanning
 
class  NaviSpeedDecider
 NaviSpeedDecider is used to generate an appropriate speed curve of the vehicle in navigation mode. Note that NaviSpeedDecider is only used in navigation mode (turn on navigation mode by setting "FLAGS_use_navigation_mode" to "true") and do not use it in standard mode. More...
 
struct  NaviSpeedTsConstraints
 NaviSpeedTsConstraints is used to describe constraints of a t-s point. More...
 
class  NaviSpeedTsGraph
 NaviSpeedTsGraph is used to generate a t-s graph with some limits and preferred. More...
 
struct  NaviSpeedTsPoint
 NaviSpeedTsPoint is used to describe a t-s point. More...
 
class  NaviTask
 
class  Node2d
 
class  Node3d
 
class  Obstacle
 This is the class that associates an Obstacle with its path properties. An obstacle's path properties relative to a path. The s and l values are examples of path properties. The decision of an obstacle is also associated with a path. More...
 
class  OnLanePlannerDispatcher
 
class  OnLanePlanning
 
class  OpenSpaceFallbackDecider
 
class  OpenSpaceInfo
 
class  OpenSpacePreStopDecider
 
class  OpenSpaceRoiDecider
 
class  OpenSpaceTrajectoryOptimizer
 
class  OpenSpaceTrajectoryPartition
 
class  OpenSpaceTrajectoryProvider
 
struct  OpenSpaceTrajectoryThreadData
 
class  OsqpSpline1dSolver
 
class  OsqpSpline2dSolver
 
class  PathAssessmentDecider
 
class  PathBoundary
 
class  PathBoundsDecider
 
class  PathData
 
class  PathDecider
 
class  PathDecision
 PathDecision represents all obstacle decisions on one path. More...
 
class  PathLaneBorrowDecider
 
class  PathOptimizer
 
class  PathReferenceDecider
 
class  PathReuseDecider
 
class  PathTimeGraph
 
class  PathTimeHeuristicOptimizer
 PathTimeHeuristicOptimizer does ST graph speed planning with dynamic programming algorithm. More...
 
class  PiecewiseAccelerationTrajectory1d
 
class  PiecewiseBrakingTrajectoryGenerator
 
class  PiecewiseJerkPathIpoptSolver
 
class  PiecewiseJerkPathOptimizer
 
class  PiecewiseJerkPathProblem
 
class  PiecewiseJerkProblem
 
class  PiecewiseJerkSpeedNonlinearIpoptInterface
 
class  PiecewiseJerkSpeedNonlinearOptimizer
 
class  PiecewiseJerkSpeedOptimizer
 
class  PiecewiseJerkSpeedProblem
 
class  PiecewiseJerkTrajectory1d
 
class  PiecewiseQuinticSpiralPath
 
class  PiecewiseTrajectory1d
 
class  Planner
 Planner is a base class for specific planners. It contains a pure virtual function Plan which must be implemented in derived class. More...
 
class  PlannerDispatcher
 
class  PlannerWithReferenceLine
 
class  PlanningBase
 
class  PlanningComponent
 
class  PlanningContext
 
class  PlanningTestBase
 
class  PolynomialCurve1d
 
class  PolynomialXd
 
class  PredictionQuerier
 
class  PublicRoadPlanner
 PublicRoadPlanner is an expectation maximization planner. More...
 
class  PublishableTrajectory
 
class  QpSplineReferenceLineSmoother
 
class  QuarticPolynomialCurve1d
 
class  QuinticPolynomialCurve1d
 
class  QuinticSpiralPath
 
class  QuinticSpiralPathWithDerivation
 
class  ReedShepp
 
struct  ReedSheppPath
 
class  ReferenceLine
 
class  ReferenceLineEnd
 
class  ReferenceLineInfo
 ReferenceLineInfo holds all data for one reference line. More...
 
class  ReferenceLineProvider
 The class of ReferenceLineProvider. It provides smoothed reference line to planning. More...
 
class  ReferenceLineSmoother
 
class  ReferencePoint
 
class  Rerouting
 
struct  RSPParam
 
struct  rss_world_model_struct
 
class  RssDecider
 
class  RTKReplayPlanner
 RTKReplayPlanner is a derived class of Planner. It reads a recorded trajectory from a trajectory file and outputs proper segment of the trajectory according to vehicle position. More...
 
class  RuleBasedStopDecider
 
struct  SamplePoint
 
class  Smoother
 
class  SpeedBoundsDecider
 
class  SpeedData
 
class  SpeedDecider
 
class  SpeedLimit
 
class  SpeedLimitDecider
 
class  SpeedOptimizer
 
class  SpeedProfileGenerator
 
class  SpiralProblemInterface
 
class  SpiralReferenceLineSmoother
 
class  Spline1d
 
class  Spline1dConstraint
 
class  Spline1dKernel
 
class  Spline1dSeg
 
class  Spline1dSolver
 
class  Spline2d
 
class  Spline2dConstraint
 
class  Spline2dKernel
 
class  Spline2dSeg
 
class  Spline2dSolver
 
class  SplineSegKernel
 
class  StandingStillTrajectory1d
 
class  STBoundary
 
class  STBoundaryMapper
 
class  STBoundsDecider
 
class  STDrivingLimits
 
class  StGapEstimator
 
class  StGraphData
 
class  StGraphPoint
 
class  STGuideLine
 
class  STObstaclesProcessor
 
class  StopSign
 
class  STPoint
 
class  Task
 
class  TaskFactory
 
class  ThreadSafeIndexedList
 
class  TrafficDecider
 Create traffic related decision in this class. The created obstacles is added to obstacles_, and the decision is added to obstacles_ Traffic obstacle examples include: More...
 
class  TrafficLight
 
class  TrafficRule
 
class  Trajectory1dGenerator
 
class  TrajectoryCombiner
 
class  TrajectoryCost
 
class  TrajectoryEvaluator
 
class  TrajectoryImitationLibtorchInference
 
class  TrajectoryOptimizer
 
class  TrajectoryStitcher
 
class  WaypointSampler
 
class  YieldSign
 

Typedefs

typedef IndexedList< std::string, ObstacleIndexedObstacles
 
typedef ThreadSafeIndexedList< std::string, ObstacleThreadSafeIndexedObstacles
 
typedef std::pair< DiscretizedTrajectory, canbus::Chassis::GearPosition > TrajGearPair
 

Enumerations

enum  VirtualObjectType {
  VirtualObjectType::DESTINATION = 0, VirtualObjectType::CROSSWALK = 1, VirtualObjectType::TRAFFIC_LIGHT = 2, VirtualObjectType::CLEAR_ZONE = 3,
  VirtualObjectType::REROUTE = 4, VirtualObjectType::DECISION_JUMP = 5, VirtualObjectType::PRIORITY = 6
}
 

Functions

bool IsNonmovableObstacle (const ReferenceLineInfo &reference_line_info, const Obstacle &obstacle)
 
bool IsBlockingObstacleToSidePass (const Frame &frame, const Obstacle *obstacle, double block_obstacle_min_speed, double min_front_sidepass_distance, bool enable_obstacle_blocked_check)
 Decide whether an obstacle is a blocking one that needs to be side-passed. More...
 
double GetDistanceBetweenADCAndObstacle (const Frame &frame, const Obstacle *obstacle)
 
bool IsBlockingDrivingPathObstacle (const ReferenceLine &reference_line, const Obstacle *obstacle)
 
bool IsParkedVehicle (const ReferenceLine &reference_line, const Obstacle *obstacle)
 
 DECLARE_string (test_routing_response_file)
 
 DECLARE_string (test_localization_file)
 
 DECLARE_string (test_chassis_file)
 
 DECLARE_string (test_data_dir)
 
 DECLARE_string (test_prediction_file)
 
 DECLARE_string (test_traffic_light_file)
 
 DECLARE_string (test_relative_map_file)
 
 DECLARE_string (test_previous_planning_file)
 
bool InitialCuda ()
 
__global__ void fill_lower_left_gpu (int *iRow, int *jCol, unsigned int *rind_L, unsigned int *cind_L, const int nnz_L)
 
template<typename T >
__global__ void data_transfer_gpu (T *dst, const T *src, const int size)
 
bool fill_lower_left (int *iRow, int *jCol, unsigned int *rind_L, unsigned int *cind_L, const int nnz_L)
 
template<typename T >
bool data_transfer (T *dst, const T *src, const int size)
 
int ContainsOutOnReverseLane (const std::vector< std::tuple< double, PathData::PathPointType, double >> &path_point_decision)
 
int GetBackToInLaneIndex (const std::vector< std::tuple< double, PathData::PathPointType, double >> &path_point_decision)
 
bool ComparePathData (const PathData &lhs, const PathData &rhs, const Obstacle *blocking_obstacle)
 
bool IsWithinPathDeciderScopeObstacle (const Obstacle &obstacle)
 

Variables

constexpr double kObsSpeedIgnoreThreshold = 100.0
 
constexpr double kPathBoundsDeciderHorizon = 100.0
 
constexpr double kPathBoundsDeciderResolution = 0.5
 
constexpr double kDefaultLaneWidth = 5.0
 
constexpr double kDefaultRoadWidth = 20.0
 
constexpr int kNumExtraTailBoundPoint = 20
 
constexpr double kPulloverLonSearchCoeff = 1.5
 
constexpr double kPulloverLatSearchCoeff = 1.25
 
constexpr double kSTBoundsDeciderResolution = 0.1
 
constexpr double kSTPassableThreshold = 3.0
 
constexpr double kADCSafetyLBuffer = 0.1
 
constexpr double kSIgnoreThreshold = 0.01
 
constexpr double kTIgnoreThreshold = 0.1
 
constexpr double kOvertakenObsCautionTime = 0.5
 

Detailed Description

apollo::planning

Typedef Documentation

◆ IndexedObstacles

◆ ThreadSafeIndexedObstacles

◆ TrajGearPair

typedef std::pair<DiscretizedTrajectory, canbus::Chassis::GearPosition> apollo::planning::TrajGearPair

Enumeration Type Documentation

◆ VirtualObjectType

Enumerator
DESTINATION 
CROSSWALK 
TRAFFIC_LIGHT 
CLEAR_ZONE 
REROUTE 
DECISION_JUMP 
PRIORITY 

Function Documentation

◆ ComparePathData()

bool apollo::planning::ComparePathData ( const PathData lhs,
const PathData rhs,
const Obstacle blocking_obstacle 
)

◆ ContainsOutOnReverseLane()

int apollo::planning::ContainsOutOnReverseLane ( const std::vector< std::tuple< double, PathData::PathPointType, double >> &  path_point_decision)

◆ data_transfer()

template<typename T >
bool apollo::planning::data_transfer ( T *  dst,
const T *  src,
const int  size 
)

◆ data_transfer_gpu()

template<typename T >
__global__ void apollo::planning::data_transfer_gpu ( T *  dst,
const T *  src,
const int  size 
)

◆ DECLARE_string() [1/8]

apollo::planning::DECLARE_string ( test_routing_response_file  )

◆ DECLARE_string() [2/8]

apollo::planning::DECLARE_string ( test_localization_file  )

◆ DECLARE_string() [3/8]

apollo::planning::DECLARE_string ( test_chassis_file  )

◆ DECLARE_string() [4/8]

apollo::planning::DECLARE_string ( test_data_dir  )

◆ DECLARE_string() [5/8]

apollo::planning::DECLARE_string ( test_prediction_file  )

◆ DECLARE_string() [6/8]

apollo::planning::DECLARE_string ( test_traffic_light_file  )

◆ DECLARE_string() [7/8]

apollo::planning::DECLARE_string ( test_relative_map_file  )

◆ DECLARE_string() [8/8]

apollo::planning::DECLARE_string ( test_previous_planning_file  )

◆ fill_lower_left()

bool apollo::planning::fill_lower_left ( int *  iRow,
int *  jCol,
unsigned int *  rind_L,
unsigned int *  cind_L,
const int  nnz_L 
)

◆ fill_lower_left_gpu()

__global__ void apollo::planning::fill_lower_left_gpu ( int *  iRow,
int *  jCol,
unsigned int *  rind_L,
unsigned int *  cind_L,
const int  nnz_L 
)

◆ GetBackToInLaneIndex()

int apollo::planning::GetBackToInLaneIndex ( const std::vector< std::tuple< double, PathData::PathPointType, double >> &  path_point_decision)

◆ GetDistanceBetweenADCAndObstacle()

double apollo::planning::GetDistanceBetweenADCAndObstacle ( const Frame frame,
const Obstacle obstacle 
)

◆ InitialCuda()

bool apollo::planning::InitialCuda ( )

◆ IsBlockingDrivingPathObstacle()

bool apollo::planning::IsBlockingDrivingPathObstacle ( const ReferenceLine reference_line,
const Obstacle obstacle 
)

◆ IsBlockingObstacleToSidePass()

bool apollo::planning::IsBlockingObstacleToSidePass ( const Frame frame,
const Obstacle obstacle,
double  block_obstacle_min_speed,
double  min_front_sidepass_distance,
bool  enable_obstacle_blocked_check 
)

Decide whether an obstacle is a blocking one that needs to be side-passed.

Parameters
Theframe that contains reference_line and other info.
Theobstacle of interest.
Thespeed threshold to tell whether an obstacle is stopped.
Theminimum distance to front blocking obstacle for side-pass. (if too close, don't side-pass for safety consideration)
Whetherto take into consideration that the blocking obstacle itself is blocked by others as well. In other words, if the front blocking obstacle is blocked by others, then don't try to side-pass it. (Parked obstacles are never blocked by others)

◆ IsNonmovableObstacle()

bool apollo::planning::IsNonmovableObstacle ( const ReferenceLineInfo reference_line_info,
const Obstacle obstacle 
)

◆ IsParkedVehicle()

bool apollo::planning::IsParkedVehicle ( const ReferenceLine reference_line,
const Obstacle obstacle 
)

◆ IsWithinPathDeciderScopeObstacle()

bool apollo::planning::IsWithinPathDeciderScopeObstacle ( const Obstacle obstacle)

Variable Documentation

◆ kADCSafetyLBuffer

constexpr double apollo::planning::kADCSafetyLBuffer = 0.1

◆ kDefaultLaneWidth

constexpr double apollo::planning::kDefaultLaneWidth = 5.0

◆ kDefaultRoadWidth

constexpr double apollo::planning::kDefaultRoadWidth = 20.0

◆ kNumExtraTailBoundPoint

constexpr int apollo::planning::kNumExtraTailBoundPoint = 20

◆ kObsSpeedIgnoreThreshold

constexpr double apollo::planning::kObsSpeedIgnoreThreshold = 100.0

◆ kOvertakenObsCautionTime

constexpr double apollo::planning::kOvertakenObsCautionTime = 0.5

◆ kPathBoundsDeciderHorizon

constexpr double apollo::planning::kPathBoundsDeciderHorizon = 100.0

◆ kPathBoundsDeciderResolution

constexpr double apollo::planning::kPathBoundsDeciderResolution = 0.5

◆ kPulloverLatSearchCoeff

constexpr double apollo::planning::kPulloverLatSearchCoeff = 1.25

◆ kPulloverLonSearchCoeff

constexpr double apollo::planning::kPulloverLonSearchCoeff = 1.5

◆ kSIgnoreThreshold

constexpr double apollo::planning::kSIgnoreThreshold = 0.01

◆ kSTBoundsDeciderResolution

constexpr double apollo::planning::kSTBoundsDeciderResolution = 0.1

◆ kSTPassableThreshold

constexpr double apollo::planning::kSTPassableThreshold = 3.0

◆ kTIgnoreThreshold

constexpr double apollo::planning::kTIgnoreThreshold = 0.1