Skip to content

Commit 8a9f43d

Browse files
refactor(behavior_path_planner): remove maximum drivable area visualization (autowarefoundation#5963)
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 092a67d commit 8a9f43d

File tree

8 files changed

+0
-135
lines changed

8 files changed

+0
-135
lines changed

planning/behavior_path_planner/config/behavior_path_planner.param.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,6 @@
2525
input_path_interval: 2.0
2626
output_path_interval: 2.0
2727

28-
visualize_maximum_drivable_area: true
29-
3028
lane_following:
3129
drivable_area_right_bound_offset: 0.0
3230
drivable_area_left_bound_offset: 0.0

planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -166,7 +166,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node
166166
const BehaviorModuleOutput & output);
167167

168168
// debug
169-
rclcpp::Publisher<MarkerArray>::SharedPtr debug_maximum_drivable_area_publisher_;
170169
rclcpp::Publisher<AvoidanceDebugMsgArray>::SharedPtr debug_avoidance_msg_array_publisher_;
171170
rclcpp::Publisher<MarkerArray>::SharedPtr debug_turn_signal_info_publisher_;
172171

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

-12
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
7373
debug_avoidance_msg_array_publisher_ =
7474
create_publisher<AvoidanceDebugMsgArray>("~/debug/avoidance_debug_message_array", 1);
7575

76-
if (planner_data_->parameters.visualize_maximum_drivable_area) {
77-
debug_maximum_drivable_area_publisher_ =
78-
create_publisher<MarkerArray>("~/maximum_drivable_area", 1);
79-
}
80-
8176
debug_turn_signal_info_publisher_ = create_publisher<MarkerArray>("~/debug/turn_signal_info", 1);
8277

8378
bound_publisher_ = create_publisher<MarkerArray>("~/debug/bound", 1);
@@ -264,7 +259,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
264259
p.enable_cog_on_centerline = declare_parameter<bool>("enable_cog_on_centerline");
265260
p.input_path_interval = declare_parameter<double>("input_path_interval");
266261
p.output_path_interval = declare_parameter<double>("output_path_interval");
267-
p.visualize_maximum_drivable_area = declare_parameter<bool>("visualize_maximum_drivable_area");
268262
p.ego_nearest_dist_threshold = declare_parameter<double>("ego_nearest_dist_threshold");
269263
p.ego_nearest_yaw_threshold = declare_parameter<double>("ego_nearest_yaw_threshold");
270264

@@ -447,12 +441,6 @@ void BehaviorPathPlannerNode::run()
447441

448442
planner_data_->prev_route_id = planner_data_->route_handler->getRouteUuid();
449443

450-
if (planner_data_->parameters.visualize_maximum_drivable_area) {
451-
const auto maximum_drivable_area = marker_utils::createFurthestLineStringMarkerArray(
452-
utils::getMaximumDrivableArea(planner_data_));
453-
debug_maximum_drivable_area_publisher_->publish(maximum_drivable_area);
454-
}
455-
456444
lk_pd.unlock(); // release planner_data_
457445

458446
planner_manager_->print();

planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/utils.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,6 @@ MarkerArray createLaneletsAreaMarkerArray(
8181
const std::vector<lanelet::ConstLanelet> & lanelets, std::string && ns, const float & r,
8282
const float & g, const float & b);
8383

84-
MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3d & linestrings);
85-
8684
MarkerArray createPolygonMarkerArray(
8785
const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r,
8886
const float & g, const float & b, const float & w = 0.3);

planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -76,9 +76,6 @@ struct BehaviorPathPlannerParameters
7676
double right_over_hang;
7777
double base_link2front;
7878
double base_link2rear;
79-
80-
// maximum drivable area visualization
81-
bool visualize_maximum_drivable_area;
8279
};
8380

8481
#endif // BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -47,9 +47,6 @@ void generateDrivableArea(
4747
PathWithLaneId & path, const double vehicle_length, const double offset,
4848
const bool is_driving_forward = true);
4949

50-
lanelet::ConstLineStrings3d getMaximumDrivableArea(
51-
const std::shared_ptr<const PlannerData> & planner_data);
52-
5350
/**
5451
* @brief Expand the borders of the given lanelets
5552
* @param [in] drivable_lanes lanelets to expand

planning/behavior_path_planner_common/src/marker_utils/utils.cpp

-84
Original file line numberDiff line numberDiff line change
@@ -236,90 +236,6 @@ MarkerArray createLaneletsAreaMarkerArray(
236236
return msg;
237237
}
238238

239-
MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3d & linestrings)
240-
{
241-
if (linestrings.empty()) {
242-
return MarkerArray();
243-
}
244-
245-
Marker marker = createDefaultMarker(
246-
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "shared_linestring_lanelets", 0L, Marker::LINE_STRIP,
247-
createMarkerScale(0.3, 0.0, 0.0), createMarkerColor(0.996, 0.658, 0.466, 0.999));
248-
marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0);
249-
250-
const auto reserve_size = linestrings.size() / 2;
251-
lanelet::ConstLineStrings3d lefts;
252-
lanelet::ConstLineStrings3d rights;
253-
lefts.reserve(reserve_size);
254-
rights.reserve(reserve_size);
255-
256-
size_t total_marker_reserve_size{0};
257-
for (size_t idx = 1; idx < linestrings.size(); idx += 2) {
258-
rights.emplace_back(linestrings.at(idx - 1));
259-
lefts.emplace_back(linestrings.at(idx));
260-
261-
for (const auto & ls : linestrings.at(idx - 1).basicLineString()) {
262-
total_marker_reserve_size += ls.size();
263-
}
264-
for (const auto & ls : linestrings.at(idx).basicLineString()) {
265-
total_marker_reserve_size += ls.size();
266-
}
267-
}
268-
269-
if (!total_marker_reserve_size) {
270-
marker.points.reserve(total_marker_reserve_size);
271-
}
272-
273-
const auto & first_ls = lefts.front().basicLineString();
274-
for (const auto & ls : first_ls) {
275-
marker.points.push_back(createPoint(ls.x(), ls.y(), ls.z()));
276-
}
277-
278-
for (auto idx = lefts.cbegin() + 1; idx != lefts.cend(); ++idx) {
279-
Point front = createPoint(
280-
idx->basicLineString().front().x(), idx->basicLineString().front().y(),
281-
idx->basicLineString().front().z());
282-
Point front_inverted = createPoint(
283-
idx->invert().basicLineString().front().x(), idx->invert().basicLineString().front().y(),
284-
idx->invert().basicLineString().front().z());
285-
286-
const auto & marker_back = marker.points.back();
287-
const bool isFrontNear = tier4_autoware_utils::calcDistance2d(marker_back, front) <
288-
tier4_autoware_utils::calcDistance2d(marker_back, front_inverted);
289-
const auto & left_ls = (isFrontNear) ? idx->basicLineString() : idx->invert().basicLineString();
290-
for (const auto & left_l : left_ls) {
291-
marker.points.push_back(createPoint(left_l.x(), left_l.y(), left_l.z()));
292-
}
293-
}
294-
295-
for (auto idx = rights.crbegin(); idx != rights.crend(); ++idx) {
296-
Point front = createPoint(
297-
idx->basicLineString().front().x(), idx->basicLineString().front().y(),
298-
idx->basicLineString().front().z());
299-
Point front_inverted = createPoint(
300-
idx->invert().basicLineString().front().x(), idx->invert().basicLineString().front().y(),
301-
idx->invert().basicLineString().front().z());
302-
303-
const auto & marker_back = marker.points.back();
304-
const bool isFrontFurther = tier4_autoware_utils::calcDistance2d(marker_back, front) >
305-
tier4_autoware_utils::calcDistance2d(marker_back, front_inverted);
306-
const auto & right_ls =
307-
(isFrontFurther) ? idx->basicLineString() : idx->invert().basicLineString();
308-
for (auto ls = right_ls.crbegin(); ls != right_ls.crend(); ++ls) {
309-
marker.points.push_back(createPoint(ls->x(), ls->y(), ls->z()));
310-
}
311-
}
312-
313-
if (!marker.points.empty()) {
314-
marker.points.push_back(marker.points.front());
315-
}
316-
317-
MarkerArray msg;
318-
319-
msg.markers.push_back(marker);
320-
return msg;
321-
}
322-
323239
MarkerArray createPolygonMarkerArray(
324240
const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r,
325241
const float & g, const float & b, const float & w)

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

-28
Original file line numberDiff line numberDiff line change
@@ -1017,34 +1017,6 @@ void generateDrivableArea(
10171017
path.right_bound = modified_right_bound;
10181018
}
10191019

1020-
// TODO(Azu) Some parts of is the same with generateCenterLinePath. Therefore it might be better if
1021-
// we can refactor some of the code for better readability
1022-
lanelet::ConstLineStrings3d getMaximumDrivableArea(
1023-
const std::shared_ptr<const PlannerData> & planner_data)
1024-
{
1025-
const auto & p = planner_data->parameters;
1026-
const auto & route_handler = planner_data->route_handler;
1027-
const auto & ego_pose = planner_data->self_odometry->pose.pose;
1028-
1029-
lanelet::ConstLanelet current_lane;
1030-
if (!route_handler->getClosestLaneletWithinRoute(ego_pose, &current_lane)) {
1031-
RCLCPP_ERROR(
1032-
rclcpp::get_logger("behavior_path_planner").get_child("utils"),
1033-
"failed to find closest lanelet within route!!!");
1034-
return {};
1035-
}
1036-
1037-
const auto current_lanes = route_handler->getLaneletSequence(
1038-
current_lane, ego_pose, p.backward_path_length, p.forward_path_length);
1039-
lanelet::ConstLineStrings3d linestring_shared;
1040-
for (const auto & lane : current_lanes) {
1041-
lanelet::ConstLineStrings3d furthest_line = route_handler->getFurthestLinestring(lane);
1042-
linestring_shared.insert(linestring_shared.end(), furthest_line.begin(), furthest_line.end());
1043-
}
1044-
1045-
return linestring_shared;
1046-
}
1047-
10481020
std::vector<DrivableLanes> expandLanelets(
10491021
const std::vector<DrivableLanes> & drivable_lanes, const double left_bound_offset,
10501022
const double right_bound_offset, const std::vector<std::string> & types_to_skip)

0 commit comments

Comments
 (0)