|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 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 | +#include "autoware/motion_utils/trajectory/path_shift.hpp" |
| 16 | + |
| 17 | +#include "autoware/motion_utils/trajectory/trajectory.hpp" |
| 18 | + |
| 19 | +namespace autoware::motion_utils |
| 20 | +{ |
| 21 | +double calc_feasible_velocity_from_jerk( |
| 22 | + const double lateral, const double jerk, const double longitudinal_distance) |
| 23 | +{ |
| 24 | + const double j = std::abs(jerk); |
| 25 | + const double l = std::abs(lateral); |
| 26 | + const double d = std::abs(longitudinal_distance); |
| 27 | + if (j < 1.0e-8 || l < 1.0e-8) { |
| 28 | + const std::string error_message( |
| 29 | + std::string(__func__) + ": Failed to calculate velocity due to invalid arg"); |
| 30 | + RCLCPP_WARN(get_logger(), "%s", error_message.c_str()); |
| 31 | + return 1.0e10; |
| 32 | + } |
| 33 | + return d / (4.0 * std::pow(0.5 * l / j, 1.0 / 3.0)); |
| 34 | +} |
| 35 | + |
| 36 | +double calc_lateral_dist_from_jerk( |
| 37 | + const double longitudinal, const double jerk, const double velocity) |
| 38 | +{ |
| 39 | + const double j = std::abs(jerk); |
| 40 | + const double d = std::abs(longitudinal); |
| 41 | + const double v = std::abs(velocity); |
| 42 | + |
| 43 | + if (j < 1.0e-8 || v < 1.0e-8) { |
| 44 | + const std::string error_message( |
| 45 | + std::string(__func__) + ": Failed to calculate lateral distance due to invalid arg"); |
| 46 | + RCLCPP_WARN(get_logger(), "%s", error_message.c_str()); |
| 47 | + return 1.0e10; |
| 48 | + } |
| 49 | + return 2.0 * std::pow(d / (4.0 * v), 3.0) * j; |
| 50 | +} |
| 51 | + |
| 52 | +double calc_longitudinal_dist_from_jerk( |
| 53 | + const double lateral, const double jerk, const double velocity) |
| 54 | +{ |
| 55 | + const double j = std::abs(jerk); |
| 56 | + const double l = std::abs(lateral); |
| 57 | + const double v = std::abs(velocity); |
| 58 | + if (j < 1.0e-8) { |
| 59 | + const std::string error_message( |
| 60 | + std::string(__func__) + ": Failed to calculate longitudinal distance due to invalid arg"); |
| 61 | + RCLCPP_WARN(get_logger(), "%s", error_message.c_str()); |
| 62 | + return 1.0e10; |
| 63 | + } |
| 64 | + return 4.0 * std::pow(0.5 * l / j, 1.0 / 3.0) * v; |
| 65 | +} |
| 66 | + |
| 67 | +double calc_shift_time_from_jerk(const double lateral, const double jerk, const double acc) |
| 68 | +{ |
| 69 | + const double j = std::abs(jerk); |
| 70 | + const double a = std::abs(acc); |
| 71 | + const double l = std::abs(lateral); |
| 72 | + if (j < 1.0e-8 || a < 1.0e-8) { |
| 73 | + const std::string error_message( |
| 74 | + std::string(__func__) + ": Failed to calculate shift time due to invalid arg"); |
| 75 | + RCLCPP_WARN(get_logger(), "%s", error_message.c_str()); |
| 76 | + return 1.0e10; // TODO(Horibe) maybe invalid arg? |
| 77 | + } |
| 78 | + |
| 79 | + // time with constant jerk |
| 80 | + double tj = a / j; |
| 81 | + |
| 82 | + // time with constant acceleration (zero jerk) |
| 83 | + double ta = (std::sqrt(a * a + 4.0 * j * j * l / a) - 3.0 * a) / (2.0 * j); |
| 84 | + |
| 85 | + if (ta < 0.0) { |
| 86 | + // it will not hit the acceleration limit this time |
| 87 | + tj = std::pow(l / (2.0 * j), 1.0 / 3.0); |
| 88 | + ta = 0.0; |
| 89 | + } |
| 90 | + |
| 91 | + const double t_total = 4.0 * tj + 2.0 * ta; |
| 92 | + return t_total; |
| 93 | +} |
| 94 | + |
| 95 | +double calc_jerk_from_lat_lon_distance( |
| 96 | + const double lateral, const double longitudinal, const double velocity) |
| 97 | +{ |
| 98 | + constexpr double ep = 1.0e-3; |
| 99 | + const double lat = std::abs(lateral); |
| 100 | + const double lon = std::max(std::abs(longitudinal), ep); |
| 101 | + const double v = std::abs(velocity); |
| 102 | + return 0.5 * lat * std::pow(4.0 * v / lon, 3); |
| 103 | +} |
| 104 | + |
| 105 | +} // namespace autoware::motion_utils |
0 commit comments