Skip to content

Commit 6d425f8

Browse files
authored
fix(behavior_path_planner): use common ego nearest search for lane_following (#1686)
* fix(behavior_path_planner): use common ego nearest search Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix ci error Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix todo's name Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * apply pre-commit Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 4f7b0da commit 6d425f8

22 files changed

+274
-299
lines changed

planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp

+18-2
Original file line numberDiff line numberDiff line change
@@ -120,8 +120,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node
120120
PathWithLaneId modifyPathForSmoothGoalConnection(
121121
const PathWithLaneId & path) const; // (TODO) move to util
122122

123-
void clipPathLength(PathWithLaneId & path) const; // (TODO) move to util
124-
125123
/**
126124
* @brief Execute behavior tree and publish planned data.
127125
*/
@@ -152,6 +150,24 @@ class BehaviorPathPlannerNode : public rclcpp::Node
152150
* @brief check path if it is unsafe or forced
153151
*/
154152
bool isForcedCandidatePath() const;
153+
154+
template <class T>
155+
size_t findEgoIndex(const std::vector<T> & points) const
156+
{
157+
const auto & p = planner_data_;
158+
return motion_utils::findFirstNearestIndexWithSoftConstraints(
159+
points, p->self_pose->pose, p->parameters.ego_nearest_dist_threshold,
160+
p->parameters.ego_nearest_yaw_threshold);
161+
}
162+
163+
template <class T>
164+
size_t findEgoSegmentIndex(const std::vector<T> & points) const
165+
{
166+
const auto & p = planner_data_;
167+
return motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
168+
points, p->self_pose->pose, p->parameters.ego_nearest_dist_threshold,
169+
p->parameters.ego_nearest_yaw_threshold);
170+
}
155171
};
156172
} // namespace behavior_path_planner
157173

planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@ struct BehaviorPathPlannerParameters
4141

4242
double path_interval;
4343

44+
double ego_nearest_dist_threshold;
45+
double ego_nearest_yaw_threshold;
46+
4447
// vehicle info
4548
vehicle_info_util::VehicleInfo vehicle_info;
4649
double wheel_base;

planning/behavior_path_planner/include/behavior_path_planner/path_utilities.hpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -41,17 +41,18 @@ std::vector<double> calcPathArcLengthArray(
4141
const PathWithLaneId & path, size_t start = 0, size_t end = std::numeric_limits<size_t>::max(),
4242
double offset = 0.0);
4343

44-
double calcPathArcLength(
45-
const PathWithLaneId & path, size_t start = 0, size_t end = std::numeric_limits<size_t>::max());
46-
4744
PathWithLaneId resamplePathWithSpline(const PathWithLaneId & path, double interval);
4845

4946
Path toPath(const PathWithLaneId & input);
5047

51-
size_t getIdxByArclength(const PathWithLaneId & path, const Pose & origin, const double signed_arc);
48+
size_t getIdxByArclength(
49+
const PathWithLaneId & path, const size_t target_idx, const double signed_arc);
50+
51+
void clipPathLength(
52+
PathWithLaneId & path, const size_t target_idx, const double forward, const double backward);
5253

5354
void clipPathLength(
54-
PathWithLaneId & path, const Pose base_pose, const double forward, const double backward);
55+
PathWithLaneId & path, const size_t target_idx, const BehaviorPathPlannerParameters & params);
5556

5657
std::pair<TurnIndicatorsCommand, double> getPathTurnSignal(
5758
const lanelet::ConstLanelets & current_lanes, const ShiftedPath & path,

planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -260,8 +260,6 @@ class AvoidanceModule : public SceneModuleInterface
260260
PathWithLaneId calcCenterLinePath(
261261
const std::shared_ptr<const PlannerData> & planner_data, const PoseStamped & pose) const;
262262

263-
void clipPathLength(PathWithLaneId & path) const;
264-
265263
// TODO(Horibe): think later.
266264
// for unique ID
267265
mutable uint64_t original_unique_id = 0; // TODO(Horibe) remove mutable

planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/util.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,8 @@ bool isLaneChangePathSafe(
7474
const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes,
7575
const lanelet::ConstLanelets & target_lanes,
7676
const PredictedObjects::ConstSharedPtr dynamic_objects, const Pose & current_pose,
77-
const Twist & current_twist, const BehaviorPathPlannerParameters & common_parameters,
77+
const size_t current_seg_idx, const Twist & current_twist,
78+
const BehaviorPathPlannerParameters & common_parameters,
7879
const behavior_path_planner::LaneChangeParameters & lane_change_parameters,
7980
std::unordered_map<std::string, CollisionCheckDebug> & debug_data, const bool use_buffer = true,
8081
const double acceleration = 0.0);

planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_over/util.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ bool isPullOverPathSafe(
6565
const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes,
6666
const lanelet::ConstLanelets & target_lanes,
6767
const PredictedObjects::ConstSharedPtr dynamic_objects, const Pose & current_pose,
68-
const Twist & current_twist, const double vehicle_width,
68+
const size_t current_seg_idx, const Twist & current_twist, const double vehicle_width,
6969
const behavior_path_planner::PullOverParameters & ros_parameters, const bool use_buffer = true,
7070
const double acceleration = 0.0);
7171
bool hasEnoughDistance(

planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp

+19
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include <random>
3737
#include <string>
3838
#include <utility>
39+
#include <vector>
3940

4041
namespace behavior_path_planner
4142
{
@@ -281,6 +282,24 @@ class SceneModuleInterface
281282
return uuid;
282283
}
283284

285+
template <class T>
286+
size_t findEgoIndex(const std::vector<T> & points) const
287+
{
288+
const auto & p = planner_data_;
289+
return motion_utils::findFirstNearestIndexWithSoftConstraints(
290+
points, p->self_pose->pose, p->parameters.ego_nearest_dist_threshold,
291+
p->parameters.ego_nearest_yaw_threshold);
292+
}
293+
294+
template <class T>
295+
size_t findEgoSegmentIndex(const std::vector<T> & points) const
296+
{
297+
const auto & p = planner_data_;
298+
return motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
299+
points, p->self_pose->pose, p->parameters.ego_nearest_dist_threshold,
300+
p->parameters.ego_nearest_yaw_threshold);
301+
}
302+
284303
public:
285304
BT::NodeStatus current_state_;
286305
};

planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp

+1-8
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ class PathShifter
9696
* @details The previous offset information is stored in the base_offset_.
9797
* This should be called after generate().
9898
*/
99-
void removeBehindShiftPointAndSetBaseOffset(const Point & base);
99+
void removeBehindShiftPointAndSetBaseOffset(const Pose & pose, const size_t nearest_idx);
100100

101101
////////////////////////////////////////
102102
// Utility Functions
@@ -169,13 +169,6 @@ class PathShifter
169169
*/
170170
std::vector<double> calcLateralJerk();
171171

172-
/**
173-
* @brief Calculate shift point from path arclength for start and end point.
174-
*/
175-
static bool calcShiftPointFromArcLength(
176-
const PathWithLaneId & path, const Point & origin, double dist_to_start, double dist_to_end,
177-
double shift_length, ShiftPoint * shift_point);
178-
179172
private:
180173
// The reference path along which the shift will be performed.
181174
PathWithLaneId reference_path_;

planning/behavior_path_planner/include/behavior_path_planner/turn_signal_decider.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,9 @@ class TurnSignalDecider
3535
{
3636
public:
3737
TurnIndicatorsCommand getTurnSignal(
38-
const PathWithLaneId & path, const Pose & current_pose, const RouteHandler & route_handler,
39-
const TurnIndicatorsCommand & turn_signal_plan, const double plan_distance) const;
38+
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
39+
const RouteHandler & route_handler, const TurnIndicatorsCommand & turn_signal_plan,
40+
const double plan_distance) const;
4041

4142
void setParameters(const double base_link2front, const double intersection_search_distance)
4243
{
@@ -46,7 +47,7 @@ class TurnSignalDecider
4647

4748
private:
4849
std::pair<TurnIndicatorsCommand, double> getIntersectionTurnSignal(
49-
const PathWithLaneId & path, const Pose & current_pose,
50+
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
5051
const RouteHandler & route_handler) const;
5152

5253
rclcpp::Logger logger_{

planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp

+58-8
Original file line numberDiff line numberDiff line change
@@ -99,22 +99,37 @@ void getProjectedDistancePointFromPolygons(
9999

100100
Path convertToPathFromPathWithLaneId(const PathWithLaneId & path_with_lane_id);
101101

102-
std::vector<Point> convertToPointArray(const PathWithLaneId & path);
102+
std::vector<Pose> convertToPoseArray(const PathWithLaneId & path);
103103

104104
std::vector<Point> convertToGeometryPointArray(const PathWithLaneId & path);
105105

106106
PoseArray convertToGeometryPoseArray(const PathWithLaneId & path);
107107

108108
PredictedPath convertToPredictedPath(
109-
const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & vehicle_pose,
110-
const double duration, const double resolution, const double acceleration,
111-
double min_speed = 1.0);
109+
const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & pose,
110+
const double nearest_seg_idx, const double duration, const double resolution,
111+
const double acceleration, const double min_speed = 1.0);
112112

113+
template <class T>
113114
FrenetCoordinate3d convertToFrenetCoordinate3d(
114-
const std::vector<Point> & linestring, const Point & search_point_geom);
115+
const std::vector<T> & pose_array, const Point & search_point_geom, const size_t seg_idx)
116+
{
117+
FrenetCoordinate3d frenet_coordinate;
115118

116-
FrenetCoordinate3d convertToFrenetCoordinate3d(
117-
const PathWithLaneId & path, const Point & search_point_geom);
119+
const double longitudinal_length =
120+
motion_utils::calcLongitudinalOffsetToSegment(pose_array, seg_idx, search_point_geom);
121+
frenet_coordinate.length =
122+
motion_utils::calcSignedArcLength(pose_array, 0, seg_idx) + longitudinal_length;
123+
frenet_coordinate.distance = motion_utils::calcLateralOffset(pose_array, search_point_geom);
124+
125+
return frenet_coordinate;
126+
}
127+
128+
inline FrenetCoordinate3d convertToFrenetCoordinate3d(
129+
const PathWithLaneId & path, const Point & search_point_geom, const size_t seg_idx)
130+
{
131+
return convertToFrenetCoordinate3d(path.points, search_point_geom, seg_idx);
132+
}
118133

119134
std::vector<uint64_t> getIds(const lanelet::ConstLanelets & lanelets);
120135

@@ -142,7 +157,42 @@ double getArcLengthToTargetLanelet(
142157

143158
Pose lerpByPose(const Pose & p1, const Pose & p2, const double t);
144159

145-
Point lerpByLength(const std::vector<Point> & array, const double length);
160+
inline Point lerpByPoint(const Point & p1, const Point & p2, const double t)
161+
{
162+
tf2::Vector3 v1, v2;
163+
v1.setValue(p1.x, p1.y, p1.z);
164+
v2.setValue(p2.x, p2.y, p2.z);
165+
166+
const auto lerped_point = v1.lerp(v2, t);
167+
168+
Point point;
169+
point.x = lerped_point.x();
170+
point.y = lerped_point.y();
171+
point.z = lerped_point.z();
172+
return point;
173+
}
174+
175+
template <class T>
176+
Point lerpByLength(const std::vector<T> & point_array, const double length)
177+
{
178+
Point lerped_point;
179+
if (point_array.empty()) {
180+
return lerped_point;
181+
}
182+
Point prev_geom_pt = tier4_autoware_utils::getPoint(point_array.front());
183+
double accumulated_length = 0;
184+
for (const auto & pt : point_array) {
185+
const auto & geom_pt = tier4_autoware_utils::getPoint(pt);
186+
const double distance = tier4_autoware_utils::calcDistance3d(prev_geom_pt, geom_pt);
187+
if (accumulated_length + distance > length) {
188+
return lerpByPoint(prev_geom_pt, geom_pt, (length - accumulated_length) / distance);
189+
}
190+
accumulated_length += distance;
191+
prev_geom_pt = geom_pt;
192+
}
193+
194+
return tier4_autoware_utils::getPoint(point_array.back());
195+
}
146196

147197
bool lerpByTimeStamp(const PredictedPath & path, const double t, Pose * lerped_pt);
148198

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+7-11
Original file line numberDiff line numberDiff line change
@@ -203,6 +203,8 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
203203
p.path_interval = declare_parameter<double>("path_interval");
204204
p.visualize_drivable_area_for_shared_linestrings_lanelet =
205205
declare_parameter("visualize_drivable_area_for_shared_linestrings_lanelet", true);
206+
p.ego_nearest_dist_threshold = declare_parameter<double>("ego_nearest_dist_threshold");
207+
p.ego_nearest_yaw_threshold = declare_parameter<double>("ego_nearest_yaw_threshold");
206208

207209
p.lateral_distance_max_threshold = declare_parameter("lateral_distance_max_threshold", 3.0);
208210
p.longitudinal_distance_min_threshold =
@@ -568,7 +570,9 @@ void BehaviorPathPlannerNode::run()
568570
clipped_path = modifyPathForSmoothGoalConnection(*path);
569571
}
570572

571-
clipPathLength(clipped_path);
573+
const size_t target_idx = findEgoIndex(clipped_path.points);
574+
util::clipPathLength(clipped_path, target_idx, planner_data_->parameters);
575+
572576
if (!clipped_path.points.empty()) {
573577
path_publisher_->publish(clipped_path);
574578
} else {
@@ -587,8 +591,9 @@ void BehaviorPathPlannerNode::run()
587591
turn_signal.command = TurnIndicatorsCommand::DISABLE;
588592
hazard_signal.command = output.turn_signal_info.hazard_signal.command;
589593
} else {
594+
const size_t ego_seg_idx = findEgoSegmentIndex(path->points);
590595
turn_signal = turn_signal_decider_.getTurnSignal(
591-
*path, planner_data->self_pose->pose, *(planner_data->route_handler),
596+
*path, planner_data->self_pose->pose, ego_seg_idx, *(planner_data->route_handler),
592597
output.turn_signal_info.turn_signal, output.turn_signal_info.signal_distance);
593598
hazard_signal.command = HazardLightsCommand::DISABLE;
594599
}
@@ -737,15 +742,6 @@ void BehaviorPathPlannerNode::onRoute(const HADMapRoute::ConstSharedPtr msg)
737742
}
738743
}
739744

740-
void BehaviorPathPlannerNode::clipPathLength(PathWithLaneId & path) const
741-
{
742-
const auto ego_pose = planner_data_->self_pose->pose;
743-
const double forward = planner_data_->parameters.forward_path_length;
744-
const double backward = planner_data_->parameters.backward_path_length;
745-
746-
util::clipPathLength(path, ego_pose, forward, backward);
747-
}
748-
749745
PathWithLaneId BehaviorPathPlannerNode::modifyPathForSmoothGoalConnection(
750746
const PathWithLaneId & path) const
751747
{

0 commit comments

Comments
 (0)