Apollo  6.0
Open source self driving car software
navi_speed_ts_graph.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 
22 #pragma once
23 
24 #include <limits>
25 #include <vector>
26 
28 
33 namespace apollo {
34 namespace planning {
35 
41  // The minimum timestamp of the point.
42  double t_min = 0.0;
43  // The maximum speed of the point.
44  double v_max = std::numeric_limits<double>::max();
45  // The preferred speed of the point.
46  double v_preffered = std::numeric_limits<double>::max();
47  // The maximum acceleration of the point.
48  double a_max = std::numeric_limits<double>::max();
49  // The preferred acceleration of the point.
50  double a_preffered = std::numeric_limits<double>::max();
51  // The maximum deceleration of the point.
52  double b_max = std::numeric_limits<double>::max();
53  // The preferred deceleration of the point.
54  double b_preffered = std::numeric_limits<double>::max();
55  // TODO(all): ignore
56  double da_max = std::numeric_limits<double>::max();
57  // TODO(all): ignore
58  double da_preffered = std::numeric_limits<double>::max();
59 };
60 
66  double s;
67  double t;
68  double v;
69  double a;
70  double da;
71 };
72 
79  public:
81 
90  void Reset(double s_step, double s_max, double start_v, double start_a,
91  double start_da);
92 
97  void UpdateConstraints(const NaviSpeedTsConstraints& constraints);
98 
105  void UpdateRangeConstraints(double start_s, double end_s,
106  const NaviSpeedTsConstraints& constraints);
107 
118  void UpdateObstacleConstraints(double distance, double safe_distance,
119  double following_accel_ratio, double v,
120  double cruise_speed);
121 
127  apollo::common::Status Solve(std::vector<NaviSpeedTsPoint>* points);
128 
129  private:
130  std::vector<NaviSpeedTsConstraints> constraints_;
131  double s_step_;
132  double start_v_;
133  double start_a_;
134  double start_da_;
135 };
136 
137 } // namespace planning
138 } // namespace apollo
double b_preffered
Definition: navi_speed_ts_graph.h:54
NaviSpeedTsPoint is used to describe a t-s point.
Definition: navi_speed_ts_graph.h:65
double s
Definition: navi_speed_ts_graph.h:66
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
double v_max
Definition: navi_speed_ts_graph.h:44
double v
Definition: navi_speed_ts_graph.h:68
Planning module main class. It processes GPS and IMU as input, to generate planning info...
double da_max
Definition: navi_speed_ts_graph.h:56
NaviSpeedTsGraph is used to generate a t-s graph with some limits and preferred.
Definition: navi_speed_ts_graph.h:78
double a
Definition: navi_speed_ts_graph.h:69
double v_preffered
Definition: navi_speed_ts_graph.h:46
double a_max
Definition: navi_speed_ts_graph.h:48
double b_max
Definition: navi_speed_ts_graph.h:52
double t
Definition: navi_speed_ts_graph.h:67
double a_preffered
Definition: navi_speed_ts_graph.h:50
NaviSpeedTsConstraints is used to describe constraints of a t-s point.
Definition: navi_speed_ts_graph.h:40
double da
Definition: navi_speed_ts_graph.h:70
double da_preffered
Definition: navi_speed_ts_graph.h:58
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
double t_min
Definition: navi_speed_ts_graph.h:42