Apollo  6.0
Open source self driving car software
path_assessment_decider.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2019 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 
17 #pragma once
18 
19 #include <memory>
20 #include <string>
21 #include <tuple>
22 #include <vector>
23 
24 #include "modules/planning/proto/planning_config.pb.h"
26 
27 namespace apollo {
28 namespace planning {
29 
31  public:
32  PathAssessmentDecider(const TaskConfig& config,
33  const std::shared_ptr<DependencyInjector>& injector);
34 
35  private:
41  common::Status Process(Frame* const frame,
42  ReferenceLineInfo* const reference_line_info) override;
43 
45  // Below are functions called when executing PathAssessmentDecider.
46 
47  bool IsValidRegularPath(const ReferenceLineInfo& reference_line_info,
48  const PathData& path_data);
49 
50  bool IsValidFallbackPath(const ReferenceLineInfo& reference_line_info,
51  const PathData& path_data);
52 
53  void SetPathInfo(const ReferenceLineInfo& reference_line_info,
54  PathData* const path_data);
55 
56  void TrimTailingOutLanePoints(PathData* const path_data);
57 
59  // Below are functions used when checking validity of path.
60 
61  bool IsGreatlyOffReferenceLine(const PathData& path_data);
62 
63  bool IsGreatlyOffRoad(const ReferenceLineInfo& reference_line_info,
64  const PathData& path_data);
65 
66  bool IsCollidingWithStaticObstacles(
67  const ReferenceLineInfo& reference_line_info, const PathData& path_data);
68 
69  bool IsStopOnReverseNeighborLane(const ReferenceLineInfo& reference_line_info,
70  const PathData& path_data);
71 
72  // * @brief Check if the path ever returns to the self-lane.
73  // * @param reference_line_info
74  // * @param path_data
75  // * @return It returns the last index that the path returns to self-lane.
76  // * If the path always stays within self-lane, it returns the size()-1.
77  // * If the path never returns to self-lane, returns -1.
78  // int IsReturningToSelfLane(
79  // const ReferenceLineInfo& reference_line_info, const PathData& path_data);
80 
82  // Below are functions used for setting path point type info.
83 
84  void InitPathPointDecision(
85  const PathData& path_data,
86  std::vector<std::tuple<double, PathData::PathPointType, double>>* const
87  path_point_decision);
88 
89  void SetPathPointType(
90  const ReferenceLineInfo& reference_line_info, const PathData& path_data,
91  const bool is_lane_change_path,
92  std::vector<std::tuple<double, PathData::PathPointType, double>>* const
93  path_point_decision);
94 
95  void SetObstacleDistance(
96  const ReferenceLineInfo& reference_line_info, const PathData& path_data,
97  std::vector<std::tuple<double, PathData::PathPointType, double>>* const
98  path_point_decision);
99 
100  void RecordDebugInfo(const PathData& path_data, const std::string& debug_name,
101  ReferenceLineInfo* const reference_line_info);
102 };
103 
105 // Below are helper functions.
106 
108  const std::vector<std::tuple<double, PathData::PathPointType, double>>&
109  path_point_decision);
110 
112  const std::vector<std::tuple<double, PathData::PathPointType, double>>&
113  path_point_decision);
114 
115 bool ComparePathData(const PathData& lhs, const PathData& rhs,
116  const Obstacle* blocking_obstacle);
117 
118 } // namespace planning
119 } // namespace apollo
This is the class that associates an Obstacle with its path properties. An obstacle&#39;s path properties...
Definition: obstacle.h:60
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Planning module main class. It processes GPS and IMU as input, to generate planning info...
Frame holds all data for one planning cycle.
Definition: frame.h:61
ReferenceLineInfo holds all data for one reference line.
Definition: reference_line_info.h:54
Definition: path_data.h:36
bool ComparePathData(const PathData &lhs, const PathData &rhs, const Obstacle *blocking_obstacle)
int ContainsOutOnReverseLane(const std::vector< std::tuple< double, PathData::PathPointType, double >> &path_point_decision)
PathAssessmentDecider(const TaskConfig &config, const std::shared_ptr< DependencyInjector > &injector)
Definition: decider.h:32
A general class to denote the return status of an API call. It can either be an OK status for success...
Definition: status.h:43
int GetBackToInLaneIndex(const std::vector< std::tuple< double, PathData::PathPointType, double >> &path_point_decision)
Definition: path_assessment_decider.h:30