Apollo  6.0
Open source self driving car software
backup_trajectory_generator.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 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 
21 #pragma once
22 
23 #include <functional>
24 #include <memory>
25 #include <queue>
26 #include <utility>
27 #include <vector>
28 
35 
36 namespace apollo {
37 namespace planning {
38 
40  public:
41  typedef std::pair<std::shared_ptr<Curve1d>, std::shared_ptr<Curve1d>>
43  typedef std::pair<Trajectory1dPair, double> PairCost;
44 
46  const std::array<double, 3>& init_s, const std::array<double, 3>& init_d,
47  const double init_relative_time,
48  const std::shared_ptr<CollisionChecker>& ptr_collision_checker,
49  const Trajectory1dGenerator* trajectory1d_generator);
50 
52  const std::vector<common::PathPoint>& discretized_ref_points);
53 
54  private:
55  void GenerateTrajectory1dPairs(const std::array<double, 3>& init_s,
56  const std::array<double, 3>& init_d);
57 
58  double init_relative_time_;
59 
60  std::shared_ptr<CollisionChecker> ptr_collision_checker_;
61 
62  const Trajectory1dGenerator* ptr_trajectory1d_generator_;
63 
64  struct CostComparator
65  : public std::binary_function<const Trajectory1dPair&,
66  const Trajectory1dPair&, bool> {
67  bool operator()(const Trajectory1dPair& left,
68  const Trajectory1dPair& right) const {
69  auto lon_left = left.first;
70  auto lon_right = right.first;
71  auto s_dot_left = lon_left->Evaluate(1, FLAGS_trajectory_time_length);
72  auto s_dot_right = lon_right->Evaluate(1, FLAGS_trajectory_time_length);
73  if (s_dot_left < s_dot_right) {
74  return true;
75  }
76  return false;
77  }
78  };
79 
80  std::priority_queue<Trajectory1dPair, std::vector<Trajectory1dPair>,
81  CostComparator>
82  trajectory_pair_pqueue_;
83 };
84 
85 } // namespace planning
86 } // namespace apollo
BackupTrajectoryGenerator(const std::array< double, 3 > &init_s, const std::array< double, 3 > &init_d, const double init_relative_time, const std::shared_ptr< CollisionChecker > &ptr_collision_checker, const Trajectory1dGenerator *trajectory1d_generator)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: discretized_trajectory.h:32
Planning module main class. It processes GPS and IMU as input, to generate planning info...
std::pair< std::shared_ptr< Curve1d >, std::shared_ptr< Curve1d > > Trajectory1dPair
Definition: backup_trajectory_generator.h:42
Definition: backup_trajectory_generator.h:39
DiscretizedTrajectory GenerateTrajectory(const std::vector< common::PathPoint > &discretized_ref_points)
Definition: trajectory1d_generator.h:39
std::pair< Trajectory1dPair, double > PairCost
Definition: backup_trajectory_generator.h:43