Apollo  6.0
Open source self driving car software
piecewise_braking_trajectory_generator.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 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 <memory>
24 
26 
27 namespace apollo {
28 namespace planning {
29 
31  public:
33 
34  static std::shared_ptr<Curve1d> Generate(
35  const double s_target, const double s_curr, const double v_target,
36  const double v_curr, const double a_comfort, const double d_comfort,
37  const double max_time);
38 
39  static double ComputeStopDistance(const double v, const double dec);
40 
41  static double ComputeStopDeceleration(const double dist, const double v);
42 };
43 
44 } // namespace planning
45 } // namespace apollo
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...
static double ComputeStopDistance(const double v, const double dec)
Definition: piecewise_braking_trajectory_generator.h:30
static double ComputeStopDeceleration(const double dist, const double v)
static std::shared_ptr< Curve1d > Generate(const double s_target, const double s_curr, const double v_target, const double v_curr, const double a_comfort, const double d_comfort, const double max_time)