Skip to content

Commit 8c63c61

Browse files
authored
refactor(bpp_common, motion_utils): move path shifter util functions to autoware::motion_utils (#9081)
* remove unused function Signed-off-by: Go Sakayori <gsakayori@gmail.com> * mover path shifter utils function to autoware motion utils Signed-off-by: Go Sakayori <go.sakayori@tier4.jp> * minor change in license header Signed-off-by: Go Sakayori <go.sakayori@tier4.jp> * fix warning message Signed-off-by: Go Sakayori <gsakayori@gmail.com> * remove header file Signed-off-by: Go Sakayori <gsakayori@gmail.com> --------- Signed-off-by: Go Sakayori <gsakayori@gmail.com> Signed-off-by: Go Sakayori <go.sakayori@tier4.jp>
1 parent 0de8669 commit 8c63c61

File tree

12 files changed

+210
-157
lines changed

12 files changed

+210
-157
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
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+
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_SHIFT_HPP_
16+
#define AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_SHIFT_HPP_
17+
18+
namespace autoware::motion_utils
19+
{
20+
/**
21+
* @brief Calculates the velocity required for shifting
22+
* @param lateral lateral distance
23+
* @param jerk lateral jerk
24+
* @param longitudinal_distance longitudinal distance
25+
* @return velocity
26+
*/
27+
double calc_feasible_velocity_from_jerk(
28+
const double lateral, const double jerk, const double longitudinal_distance);
29+
30+
/**
31+
* @brief Calculates the lateral distance required for shifting
32+
* @param longitudinal longitudinal distance
33+
* @param jerk lateral jerk
34+
* @param velocity velocity
35+
* @return lateral distance
36+
*/
37+
double calc_lateral_dist_from_jerk(
38+
const double longitudinal, const double jerk, const double velocity);
39+
40+
/**
41+
* @brief Calculates the lateral distance required for shifting
42+
* @param lateral lateral distance
43+
* @param jerk lateral jerk
44+
* @param velocity velocity
45+
* @return longitudinal distance
46+
*/
47+
double calc_longitudinal_dist_from_jerk(
48+
const double lateral, const double jerk, const double velocity);
49+
50+
/**
51+
* @brief Calculates the total time required for shifting
52+
* @param lateral lateral distance
53+
* @param jerk lateral jerk
54+
* @param acc lateral acceleration
55+
* @return time
56+
*/
57+
double calc_shift_time_from_jerk(const double lateral, const double jerk, const double acc);
58+
59+
/**
60+
* @brief Calculates the required jerk from lateral/longitudinal distance
61+
* @param lateral lateral distance
62+
* @param longitudinal longitudinal distance
63+
* @param velocity velocity
64+
* @return jerk
65+
*/
66+
double calc_jerk_from_lat_lon_distance(
67+
const double lateral, const double longitudinal, const double velocity);
68+
69+
} // namespace autoware::motion_utils
70+
71+
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_SHIFT_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
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

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
1919
#include "autoware/behavior_path_planner_common/utils/path_utils.hpp"
2020

21+
#include <autoware/motion_utils/trajectory/path_shift.hpp>
2122
#include <autoware_lanelet2_extension/utility/query.hpp>
2223
#include <autoware_lanelet2_extension/utility/utilities.hpp>
2324

@@ -181,7 +182,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
181182
.y;
182183

183184
// calculate shift start pose on road lane
184-
const double pull_over_distance = PathShifter::calcLongitudinalDistFromJerk(
185+
const double pull_over_distance = autoware::motion_utils::calc_longitudinal_dist_from_jerk(
185186
shift_end_road_to_target_distance, lateral_jerk, pull_over_velocity);
186187
const double before_shifted_pull_over_distance = calcBeforeShiftedArcLength(
187188
processed_prev_module_path.value(), pull_over_distance, shift_end_road_to_target_distance);

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@
2323
#include "autoware/behavior_path_planner_common/utils/traffic_light_utils.hpp"
2424
#include "autoware/behavior_path_planner_common/utils/utils.hpp"
2525

26+
#include <autoware/motion_utils/trajectory/path_shift.hpp>
27+
#include <autoware/motion_utils/trajectory/trajectory.hpp>
2628
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
2729
#include <autoware/universe_utils/math/unit_conversion.hpp>
2830
#include <autoware/universe_utils/system/time_keeper.hpp>
@@ -1612,7 +1614,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
16121614
const auto [min_lateral_acc, max_lateral_acc] =
16131615
lane_change_parameters_->lane_change_lat_acc_map.find(minimum_lane_changing_velocity);
16141616

1615-
const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk(
1617+
const auto lane_changing_time = autoware::motion_utils::calc_shift_time_from_jerk(
16161618
shift_length, lane_change_parameters_->lane_changing_lateral_jerk, max_lateral_acc);
16171619

16181620
const auto target_lane_length = common_data_ptr_->transient_data.target_lane_length;
@@ -1876,9 +1878,8 @@ bool NormalLaneChange::calcAbortPath()
18761878
PathShifter path_shifter;
18771879
path_shifter.setPath(lane_changing_path);
18781880
path_shifter.addShiftLine(shift_line);
1879-
const auto lateral_jerk =
1880-
autoware::behavior_path_planner::PathShifter::calcJerkFromLatLonDistance(
1881-
shift_line.end_shift_length, abort_start_dist, current_velocity);
1881+
const auto lateral_jerk = autoware::motion_utils::calc_jerk_from_lat_lon_distance(
1882+
shift_line.end_shift_length, abort_start_dist, current_velocity);
18821883
path_shifter.setVelocity(current_velocity);
18831884
const auto lateral_acc_range =
18841885
lane_change_parameters_->lane_change_lat_acc_map.find(current_velocity);

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
#include <autoware/behavior_path_lane_change_module/utils/calculation.hpp>
1717
#include <autoware/behavior_path_planner_common/utils/utils.hpp>
18+
#include <autoware/motion_utils/trajectory/path_shift.hpp>
1819

1920
#include <boost/geometry/algorithms/buffer.hpp>
2021

@@ -163,7 +164,7 @@ double calc_maximum_lane_change_length(
163164
const auto [min_lat_acc, max_lat_acc] =
164165
lane_change_parameters.lane_change_lat_acc_map.find(vel);
165166
const auto t_lane_changing =
166-
PathShifter::calcShiftTimeFromJerk(shift_interval, lat_jerk, max_lat_acc);
167+
autoware::motion_utils::calc_shift_time_from_jerk(shift_interval, lat_jerk, max_lat_acc);
167168
const auto lane_changing_length =
168169
vel * t_lane_changing + 0.5 * max_acc * t_lane_changing * t_lane_changing;
169170

@@ -208,7 +209,8 @@ std::vector<double> calc_all_min_lc_lengths(
208209
min_lc_lengths.reserve(shift_intervals.size());
209210

210211
const auto min_lc_length = [&](const auto shift_interval) {
211-
const auto t = PathShifter::calcShiftTimeFromJerk(shift_interval, lat_jerk, max_lat_acc);
212+
const auto t =
213+
autoware::motion_utils::calc_shift_time_from_jerk(shift_interval, lat_jerk, max_lat_acc);
212214
return min_vel * t;
213215
};
214216

@@ -248,7 +250,7 @@ std::vector<double> calc_all_max_lc_lengths(
248250
// lane changing section
249251
const auto [min_lat_acc, max_lat_acc] = lc_param_ptr->lane_change_lat_acc_map.find(vel);
250252
const auto t_lane_changing =
251-
PathShifter::calcShiftTimeFromJerk(shift_interval, lat_jerk, max_lat_acc);
253+
autoware::motion_utils::calc_shift_time_from_jerk(shift_interval, lat_jerk, max_lat_acc);
252254
const auto lane_changing_length =
253255
vel * t_lane_changing + 0.5 * max_acc * t_lane_changing * t_lane_changing;
254256

@@ -410,7 +412,7 @@ std::vector<PhaseMetrics> calc_shift_phase_metrics(
410412

411413
for (double lat_acc = min_lateral_acc; lat_acc < max_lateral_acc + eps;
412414
lat_acc += lateral_acc_resolution) {
413-
const auto lane_changing_duration = PathShifter::calcShiftTimeFromJerk(
415+
const auto lane_changing_duration = autoware::motion_utils::calc_shift_time_from_jerk(
414416
shift_length, common_data_ptr->lc_param_ptr->lane_changing_lateral_jerk, lat_acc);
415417

416418
const double lane_changing_accel = calc_lane_changing_acceleration(

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp

-31
Original file line numberDiff line numberDiff line change
@@ -108,11 +108,6 @@ class PathShifter
108108
*/
109109
std::vector<ShiftLine> getShiftLines() const { return shift_lines_; }
110110

111-
/**
112-
* @brief Get shift points size.
113-
*/
114-
size_t getShiftLinesSize() const { return shift_lines_.size(); }
115-
116111
/**
117112
* @brief Get base offset.
118113
*/
@@ -138,36 +133,10 @@ class PathShifter
138133
*/
139134
void removeBehindShiftLineAndSetBaseOffset(const size_t nearest_idx);
140135

141-
////////////////////////////////////////
142-
// Utility Functions
143-
////////////////////////////////////////
144-
145-
static double calcFeasibleVelocityFromJerk(
146-
const double lateral, const double jerk, const double longitudinal_distance);
147-
148-
static double calcLateralDistFromJerk(
149-
const double longitudinal, const double jerk, const double velocity);
150-
151-
static double calcLongitudinalDistFromJerk(
152-
const double lateral, const double jerk, const double velocity);
153-
154-
static double calcShiftTimeFromJerk(const double lateral, const double jerk, const double acc);
155-
156-
static double calcJerkFromLatLonDistance(
157-
const double lateral, const double longitudinal, const double velocity);
158-
159-
double getTotalShiftLength() const;
160-
161136
double getLastShiftLength() const;
162137

163138
std::optional<ShiftLine> getLastShiftLine() const;
164139

165-
/**
166-
* @brief Calculate the theoretical lateral jerk by spline shifting for current shift_lines_.
167-
* @return Jerk array. The size is same as the shift points.
168-
*/
169-
std::vector<double> calcLateralJerk() const;
170-
171140
private:
172141
// The reference path along which the shift will be performed.
173142
PathWithLaneId reference_path_;

0 commit comments

Comments
 (0)