scenario_simulator_v2 C++ API
longitudinal_speed_planning.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__BEHAVIOR__LONGITUDINAL_SPEED_PLANNING_HPP_
16 #define TRAFFIC_SIMULATOR__BEHAVIOR__LONGITUDINAL_SPEED_PLANNING_HPP_
17 
18 #include <traffic_simulator_msgs/msg/action_status.hpp>
19 #include <traffic_simulator_msgs/msg/dynamic_constraints.hpp>
20 #include <tuple>
21 
22 namespace traffic_simulator
23 {
24 namespace longitudinal_speed_planning
25 {
27 {
28 public:
29  explicit LongitudinalSpeedPlanner(double step_time, const std::string & entity);
30  auto getDynamicStates(
31  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
32  const geometry_msgs::msg::Twist & current_twist,
33  const geometry_msgs::msg::Accel & current_accel) const
34  -> std::tuple<geometry_msgs::msg::Twist, geometry_msgs::msg::Accel, double>;
36  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
37  const geometry_msgs::msg::Twist & current_twist,
38  const geometry_msgs::msg::Accel & current_accel) const -> double;
40  double target_speed, const geometry_msgs::msg::Twist & current_twist,
41  const geometry_msgs::msg::Accel & current_accel, double acceleration_duration,
42  const traffic_simulator_msgs::msg::DynamicConstraints & constraints)
43  -> traffic_simulator_msgs::msg::DynamicConstraints;
44  auto getRunningDistance(
45  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
46  const geometry_msgs::msg::Twist & current_twist,
47  const geometry_msgs::msg::Accel & current_accel, double current_linear_jerk) const -> double;
48  auto isAccelerating(double target_speed, const geometry_msgs::msg::Twist & current_twist) const
49  -> bool;
50  auto isDecelerating(double target_speed, const geometry_msgs::msg::Twist & current_twist) const
51  -> bool;
53  double target_speed, const geometry_msgs::msg::Twist & current_twist,
54  double tolerance = 0.01) const noexcept -> bool;
55  const double step_time;
57 
58 private:
59  auto isReachedToTargetSpeedWithConstantJerk(
60  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
61  const geometry_msgs::msg::Twist & current_twist,
62  const geometry_msgs::msg::Accel & current_accel, double duration, double tolerance = 0.01) const
63  -> bool;
64  auto getVelocityWithConstantJerk(
65  double target_speed, const geometry_msgs::msg::Twist & current_twist,
66  const geometry_msgs::msg::Accel & current_accel,
67  const traffic_simulator_msgs::msg::DynamicConstraints &, double duration) const -> double;
68  auto getVelocityWithConstantJerk(
69  const geometry_msgs::msg::Twist & current_twist,
70  const geometry_msgs::msg::Accel & current_accel, double linear_jerk, double duration) const
71  -> double;
72  auto getQuadraticAccelerationDuration(
73  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
74  const geometry_msgs::msg::Twist & current_twist,
75  const geometry_msgs::msg::Accel & current_accel) const -> double;
76  auto getLinearAccelerationDuration(
77  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
78  const geometry_msgs::msg::Twist & current_twist,
79  const geometry_msgs::msg::Accel & current_accel) const -> double;
80  auto getQuadraticAccelerationDurationWithConstantJerk(
81  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
82  const geometry_msgs::msg::Twist & current_twist,
83  const geometry_msgs::msg::Accel & current_accel) const -> double;
84  auto planLinearJerk(
85  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &,
86  const geometry_msgs::msg::Twist & current_twist,
87  const geometry_msgs::msg::Accel & current_accel) const -> double;
88  auto forward(
89  double linear_jerk, const geometry_msgs::msg::Accel &,
90  const traffic_simulator_msgs::msg::DynamicConstraints &) const -> geometry_msgs::msg::Accel;
91  auto forward(
92  const geometry_msgs::msg::Accel &, const geometry_msgs::msg::Twist &,
93  const traffic_simulator_msgs::msg::DynamicConstraints &) const -> geometry_msgs::msg::Twist;
94  auto timeDerivative(
95  const geometry_msgs::msg::Twist & before, const geometry_msgs::msg::Twist & after) const
96  -> geometry_msgs::msg::Accel;
97  auto timeDerivative(
98  const geometry_msgs::msg::Accel & before, const geometry_msgs::msg::Accel & after) const
99  -> double;
100 };
101 
102 } // namespace longitudinal_speed_planning
103 } // namespace traffic_simulator
104 
105 #endif // TRAFFIC_SIMULATOR__BEHAVIOR__LONGITUDINAL_SPEED_PLANNING_HPP_
const std::string entity
Definition: longitudinal_speed_planning.hpp:56
auto getDynamicStates(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel) const -> std::tuple< geometry_msgs::msg::Twist, geometry_msgs::msg::Accel, double >
Definition: longitudinal_speed_planning.cpp:80
auto isTargetSpeedReached(double target_speed, const geometry_msgs::msg::Twist &current_twist, double tolerance=0.01) const noexcept -> bool
Definition: longitudinal_speed_planning.cpp:124
auto getRunningDistance(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel, double current_linear_jerk) const -> double
Definition: longitudinal_speed_planning.cpp:97
auto isDecelerating(double target_speed, const geometry_msgs::msg::Twist &current_twist) const -> bool
Definition: longitudinal_speed_planning.cpp:250
auto planConstraintsFromJerkAndTimeConstraint(double target_speed, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel, double acceleration_duration, const traffic_simulator_msgs::msg::DynamicConstraints &constraints) -> traffic_simulator_msgs::msg::DynamicConstraints
Definition: longitudinal_speed_planning.cpp:40
auto getAccelerationDuration(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel) const -> double
Definition: longitudinal_speed_planning.cpp:31
auto isAccelerating(double target_speed, const geometry_msgs::msg::Twist &current_twist) const -> bool
Definition: longitudinal_speed_planning.cpp:244
LongitudinalSpeedPlanner(double step_time, const std::string &entity)
Definition: longitudinal_speed_planning.cpp:26
const double step_time
Definition: longitudinal_speed_planning.hpp:55
Definition: api.hpp:48
std::string string
Definition: junit5.hpp:26