Skip to content

Commit b5c98ef

Browse files
refactor(autoware_behavior_path_side_shift_module): refactor shift length retrieval and improve path orientation handling (#9539)
refactor(side_shift_module): refactor shift length retrieval and improve path orientation handling Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
1 parent 7b7db7a commit b5c98ef

File tree

4 files changed

+38
-28
lines changed

4 files changed

+38
-28
lines changed

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -87,8 +87,6 @@ class SideShiftModule : public SceneModuleInterface
8787
// const methods
8888
void publishPath(const PathWithLaneId & path) const;
8989

90-
double getClosestShiftLength() const;
91-
9290
// member
9391
PathWithLaneId refined_path_{};
9492
PathWithLaneId reference_path_{};

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp

+18-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef AUTOWARE__BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_
1616
#define AUTOWARE__BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_
1717

18+
#include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"
19+
1820
#include <geometry_msgs/msg/point.hpp>
1921
#include <geometry_msgs/msg/pose.hpp>
2022
#include <geometry_msgs/msg/transform_stamped.hpp>
@@ -27,9 +29,24 @@ using geometry_msgs::msg::Pose;
2729
using geometry_msgs::msg::TransformStamped;
2830
using tier4_planning_msgs::msg::PathWithLaneId;
2931

32+
/**
33+
* @brief Sets the orientation (yaw angle) for all points in the path.
34+
* @param [in,out] path Path with lane ID to set orientation.
35+
* @details For each point, calculates orientation based on:
36+
* - Vector to next point if not last point
37+
* - Vector from previous point if last point
38+
* - Zero angle if single point
39+
*/
3040
void setOrientation(PathWithLaneId * path);
3141

32-
bool isAlmostZero(double v);
42+
/**
43+
* @brief Gets the shift length at the closest path point to the ego position.
44+
* @param [in] shifted_path Path with shift length information.
45+
* @param [in] ego_point Current ego position.
46+
* @return Shift length at the closest path point. Returns 0.0 if path is empty.
47+
*/
48+
double getClosestShiftLength(
49+
const ShiftedPath & shifted_path, const geometry_msgs::msg::Point ego_point);
3350

3451
} // namespace autoware::behavior_path_planner
3552

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp

+11-17
Original file line numberDiff line numberDiff line change
@@ -88,8 +88,7 @@ bool SideShiftModule::isExecutionRequested() const
8888
}
8989

9090
// If the desired offset has a non-zero value, return true as we want to execute the plan.
91-
92-
const bool has_request = !isAlmostZero(requested_lateral_offset_);
91+
const bool has_request = std::fabs(requested_lateral_offset_) >= 1.0e-4;
9392
RCLCPP_DEBUG_STREAM(
9493
getLogger(), "ESS::isExecutionRequested() : " << std::boolalpha << has_request);
9594

@@ -119,14 +118,15 @@ bool SideShiftModule::canTransitSuccessState()
119118
{
120119
// Never return the FAILURE. When the desired offset is zero and the vehicle is in the original
121120
// drivable area,this module can stop the computation and return SUCCESS.
121+
constexpr double ZERO_THRESHOLD = 1.0e-4;
122122

123123
const auto isOffsetDiffAlmostZero = [this]() noexcept {
124124
const auto last_sp = path_shifter_.getLastShiftLine();
125125
if (last_sp) {
126126
const auto length = std::fabs(last_sp.value().end_shift_length);
127127
const auto lateral_offset = std::fabs(requested_lateral_offset_);
128128
const auto offset_diff = lateral_offset - length;
129-
if (!isAlmostZero(offset_diff)) {
129+
if (std::fabs(offset_diff) >= ZERO_THRESHOLD) {
130130
lateral_offset_change_request_ = true;
131131
return false;
132132
}
@@ -135,7 +135,7 @@ bool SideShiftModule::canTransitSuccessState()
135135
}();
136136

137137
const bool no_offset_diff = isOffsetDiffAlmostZero;
138-
const bool no_request = isAlmostZero(requested_lateral_offset_);
138+
const bool no_request = std::fabs(requested_lateral_offset_) < ZERO_THRESHOLD;
139139

140140
const auto no_shifted_plan = [&]() {
141141
if (prev_output_.shift_length.empty()) {
@@ -279,6 +279,11 @@ BehaviorModuleOutput SideShiftModule::plan()
279279
ShiftedPath shifted_path;
280280
path_shifter_.generate(&shifted_path);
281281

282+
if (shifted_path.path.points.empty()) {
283+
RCLCPP_ERROR(getLogger(), "Generated shift_path has no points");
284+
return {};
285+
}
286+
282287
// Reset orientation
283288
setOrientation(&shifted_path.path);
284289

@@ -345,7 +350,8 @@ ShiftLine SideShiftModule::calcShiftLine() const
345350
std::max(p->min_distance_to_start_shifting, ego_speed * p->time_to_start_shifting);
346351

347352
const double dist_to_end = [&]() {
348-
const double shift_length = requested_lateral_offset_ - getClosestShiftLength();
353+
const double shift_length =
354+
requested_lateral_offset_ - getClosestShiftLength(prev_output_, getEgoPose().position);
349355
const double jerk_shifting_distance = autoware::motion_utils::calc_longitudinal_dist_from_jerk(
350356
shift_length, p->shifting_lateral_jerk, std::max(ego_speed, p->min_shifting_speed));
351357
const double shifting_distance = std::max(jerk_shifting_distance, p->min_shifting_distance);
@@ -367,18 +373,6 @@ ShiftLine SideShiftModule::calcShiftLine() const
367373
return shift_line;
368374
}
369375

370-
double SideShiftModule::getClosestShiftLength() const
371-
{
372-
if (prev_output_.shift_length.empty()) {
373-
return 0.0;
374-
}
375-
376-
const auto ego_point = planner_data_->self_odometry->pose.pose.position;
377-
const auto closest =
378-
autoware::motion_utils::findNearestIndex(prev_output_.path.points, ego_point);
379-
return prev_output_.shift_length.at(closest);
380-
}
381-
382376
BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & path) const
383377
{
384378
BehaviorModuleOutput out;

planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -26,12 +26,6 @@ namespace autoware::behavior_path_planner
2626
{
2727
void setOrientation(PathWithLaneId * path)
2828
{
29-
if (!path) {
30-
RCLCPP_ERROR(
31-
rclcpp::get_logger("behavior_path_planner").get_child("side_shift").get_child("util"),
32-
"Pointer to path is NULL!");
33-
}
34-
3529
// Reset orientation
3630
for (size_t idx = 0; idx < path->points.size(); ++idx) {
3731
double angle = 0.0;
@@ -53,9 +47,16 @@ void setOrientation(PathWithLaneId * path)
5347
}
5448
}
5549

56-
bool isAlmostZero(double v)
50+
double getClosestShiftLength(
51+
const ShiftedPath & shifted_path, const geometry_msgs::msg::Point ego_point)
5752
{
58-
return std::fabs(v) < 1.0e-4;
53+
if (shifted_path.shift_length.empty()) {
54+
return 0.0;
55+
}
56+
57+
const auto closest =
58+
autoware::motion_utils::findNearestIndex(shifted_path.path.points, ego_point);
59+
return shifted_path.shift_length.at(closest);
5960
}
6061

6162
} // namespace autoware::behavior_path_planner

0 commit comments

Comments
 (0)