Apollo  6.0
Open source self driving car software
st_driving_limits.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 
21 #pragma once
22 
23 #include <tuple>
24 #include <utility>
25 #include <vector>
26 
27 #include "modules/common/configs/proto/vehicle_config.pb.h"
35 
36 namespace apollo {
37 namespace planning {
38 
40  public:
42 
43  void Init(const double max_acc, const double max_dec, const double max_v,
44  double curr_v);
45 
46  virtual ~STDrivingLimits() = default;
47 
53  std::pair<double, double> GetVehicleDynamicsLimits(const double t) const;
54 
64  void UpdateBlockingInfo(const double t, const double lower_s,
65  const double lower_v, const double upper_s,
66  const double upper_v);
67 
68  private:
69  // Private variables for calculating vehicle dynamic limits:
70  double max_acc_;
71  double max_dec_;
72  double max_v_;
73 
74  double upper_t0_;
75  double upper_v0_;
76  double upper_s0_;
77 
78  double lower_t0_;
79  double lower_v0_;
80  double lower_s0_;
81 
82  // The limits expressed as v vs. s, which contains the following parts:
83  // 1. speed limits at path segments with big curvatures.
84  std::vector<std::tuple<double, double, double>> curvature_speed_limits_s_v_;
85  // 2. speed limits from traffic limits (speed bumps, etc.).
86  std::vector<std::tuple<double, double, double>> traffic_speed_limits_s_v_;
87  // 3. speed limits for safety considerations when other obstacles are nearby
88  std::vector<std::tuple<double, double, double>> obstacles_speed_limits_s_v_;
89 };
90 
91 } // namespace planning
92 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
STDrivingLimits()
Definition: st_driving_limits.h:41
Planning module main class. It processes GPS and IMU as input, to generate planning info...
Definition: st_driving_limits.h:39
void Init(const double max_acc, const double max_dec, const double max_v, double curr_v)
std::pair< double, double > GetVehicleDynamicsLimits(const double t) const
Given time t, calculate the driving limits in s due to vehicle&#39;s dynamics.
void UpdateBlockingInfo(const double t, const double lower_s, const double lower_v, const double upper_s, const double upper_v)
Update the anchoring of the vehicle dynamics limits. For example, when ADC is blocked by some obstacl...
virtual ~STDrivingLimits()=default