Skip to content

Commit 6d8f026

Browse files
refactor(lane_change): combine all debug data into single struct (#6173)
* refactor(lane_change): combine all debug data into single struct Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Rename valid path → valid paths Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * move the marker creation to marker_utils Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Remove alias Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent f514bca commit 6d8f026

File tree

7 files changed

+129
-76
lines changed

7 files changed

+129
-76
lines changed

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,7 @@ class LaneChangeInterface : public SceneModuleInterface
128128

129129
bool canTransitIdleToRunningState() override;
130130

131-
void setObjectDebugVisualization() const;
131+
void updateDebugMarker() const;
132132

133133
void updateSteeringFactorPtr(const BehaviorModuleOutput & output);
134134

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp

+3-19
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_
1616

1717
#include "behavior_path_lane_change_module/utils/data_structs.hpp"
18+
#include "behavior_path_lane_change_module/utils/debug_structs.hpp"
1819
#include "behavior_path_lane_change_module/utils/path.hpp"
1920
#include "behavior_path_lane_change_module/utils/utils.hpp"
2021
#include "behavior_path_planner_common/interface/scene_module_interface.hpp"
@@ -36,7 +37,6 @@
3637
namespace behavior_path_planner
3738
{
3839
using autoware_auto_planning_msgs::msg::PathWithLaneId;
39-
using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap;
4040
using data::lane_change::PathSafetyStatus;
4141
using geometry_msgs::msg::Point;
4242
using geometry_msgs::msg::Pose;
@@ -137,19 +137,7 @@ class LaneChangeBase
137137

138138
const LaneChangeStatus & getLaneChangeStatus() const { return status_; }
139139

140-
const LaneChangePaths & getDebugValidPath() const { return debug_valid_path_; }
141-
142-
const CollisionCheckDebugMap & getDebugData() const { return object_debug_; }
143-
144-
const CollisionCheckDebugMap & getAfterApprovalDebugData() const
145-
{
146-
return object_debug_after_approval_;
147-
}
148-
149-
const LaneChangeTargetObjects & getDebugFilteredObjects() const
150-
{
151-
return debug_filtered_objects_;
152-
}
140+
const data::lane_change::Debug & getDebugData() const { return lane_change_debug_; }
153141

154142
const Pose & getEgoPose() const { return planner_data_->self_odometry->pose.pose; }
155143

@@ -257,12 +245,8 @@ class LaneChangeBase
257245
Direction direction_{Direction::NONE};
258246
LaneChangeModuleType type_{LaneChangeModuleType::NORMAL};
259247

260-
mutable LaneChangePaths debug_valid_path_{};
261-
mutable CollisionCheckDebugMap object_debug_{};
262-
mutable CollisionCheckDebugMap object_debug_after_approval_{};
263-
mutable LaneChangeTargetObjects debug_filtered_objects_{};
264-
mutable double object_debug_lifetime_{0.0};
265248
mutable StopWatch<std::chrono::milliseconds> stop_watch_;
249+
mutable data::lane_change::Debug lane_change_debug_;
266250

267251
rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr());
268252
mutable rclcpp::Clock clock_{RCL_ROS_TIME};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
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+
#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_
15+
#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_
16+
17+
#include "behavior_path_lane_change_module/utils/data_structs.hpp"
18+
#include "behavior_path_lane_change_module/utils/path.hpp"
19+
20+
#include <behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp>
21+
22+
#include <string>
23+
24+
namespace behavior_path_planner::data::lane_change
25+
{
26+
using utils::path_safety_checker::CollisionCheckDebugMap;
27+
struct Debug
28+
{
29+
std::string module_type;
30+
LaneChangePaths valid_paths;
31+
CollisionCheckDebugMap collision_check_objects;
32+
CollisionCheckDebugMap collision_check_objects_after_approval;
33+
LaneChangeTargetObjects filtered_objects;
34+
double collision_check_object_debug_lifetime{0.0};
35+
36+
void reset()
37+
{
38+
valid_paths.clear();
39+
collision_check_objects.clear();
40+
collision_check_objects_after_approval.clear();
41+
filtered_objects.current_lane.clear();
42+
filtered_objects.target_lane.clear();
43+
filtered_objects.other_lane.clear();
44+
collision_check_object_debug_lifetime = 0.0;
45+
}
46+
};
47+
} // namespace behavior_path_planner::data::lane_change
48+
49+
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,11 @@
1515
#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_
1616
#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_
1717

18+
#include "behavior_path_lane_change_module/utils/debug_structs.hpp"
1819
#include "behavior_path_lane_change_module/utils/path.hpp"
1920
#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
2021

22+
#include <visualization_msgs/msg/detail/marker_array__struct.hpp>
2123
#include <visualization_msgs/msg/marker_array.hpp>
2224

2325
#include <string>
@@ -26,6 +28,7 @@
2628
namespace marker_utils::lane_change_markers
2729
{
2830
using behavior_path_planner::LaneChangePath;
31+
using behavior_path_planner::data::lane_change::Debug;
2932
using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects;
3033
using visualization_msgs::msg::MarkerArray;
3134
MarkerArray showAllValidLaneChangePath(
@@ -37,5 +40,6 @@ MarkerArray showFilteredObjects(
3740
const ExtendedPredictedObjects & current_lane_objects,
3841
const ExtendedPredictedObjects & target_lane_objects,
3942
const ExtendedPredictedObjects & other_lane_objects, const std::string & ns);
43+
MarkerArray createDebugMarkerArray(const Debug & debug_data);
4044
} // namespace marker_utils::lane_change_markers
4145
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_

planning/behavior_path_lane_change_module/src/interface.cpp

+9-35
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ void LaneChangeInterface::updateData()
8383
if (isWaitingApproval()) {
8484
module_type_->updateLaneChangeStatus();
8585
}
86-
setObjectDebugVisualization();
86+
updateDebugMarker();
8787

8888
module_type_->updateSpecialData();
8989
module_type_->resetStopPose();
@@ -109,7 +109,8 @@ BehaviorModuleOutput LaneChangeInterface::plan()
109109

110110
stop_pose_ = module_type_->getStopPose();
111111

112-
for (const auto & [uuid, data] : module_type_->getAfterApprovalDebugData()) {
112+
const auto & lane_change_debug = module_type_->getDebugData();
113+
for (const auto & [uuid, data] : lane_change_debug.collision_check_objects_after_approval) {
113114
const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED;
114115
setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color);
115116
}
@@ -133,7 +134,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
133134
out.drivable_area_info = getPreviousModuleOutput().drivable_area_info;
134135
out.turn_signal_info = getCurrentTurnSignalInfo(out.path, out.turn_signal_info);
135136

136-
for (const auto & [uuid, data] : module_type_->getDebugData()) {
137+
const auto & lane_change_debug = module_type_->getDebugData();
138+
for (const auto & [uuid, data] : lane_change_debug.collision_check_objects) {
137139
const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED;
138140
setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color);
139141
}
@@ -291,7 +293,7 @@ bool LaneChangeInterface::canTransitFailureState()
291293

292294
bool LaneChangeInterface::canTransitIdleToRunningState()
293295
{
294-
setObjectDebugVisualization();
296+
updateDebugMarker();
295297

296298
auto log_debug_throttled = [&](std::string_view message) -> void {
297299
RCLCPP_DEBUG(getLogger(), "%s", message.data());
@@ -312,43 +314,15 @@ bool LaneChangeInterface::canTransitIdleToRunningState()
312314
return true;
313315
}
314316

315-
void LaneChangeInterface::setObjectDebugVisualization() const
317+
void LaneChangeInterface::updateDebugMarker() const
316318
{
317-
debug_marker_.markers.clear();
318319
if (!parameters_->publish_debug_marker) {
319320
return;
320321
}
321-
using marker_utils::showPolygon;
322-
using marker_utils::showPredictedPath;
323-
using marker_utils::showSafetyCheckInfo;
324-
using marker_utils::lane_change_markers::showAllValidLaneChangePath;
325-
using marker_utils::lane_change_markers::showFilteredObjects;
326-
327-
const auto debug_data = module_type_->getDebugData();
328-
const auto debug_after_approval = module_type_->getAfterApprovalDebugData();
329-
const auto debug_valid_path = module_type_->getDebugValidPath();
330-
const auto debug_filtered_objects = module_type_->getDebugFilteredObjects();
331322

332323
debug_marker_.markers.clear();
333-
const auto add = [this](const MarkerArray & added) {
334-
tier4_autoware_utils::appendMarkerArray(added, &debug_marker_);
335-
};
336-
337-
add(showAllValidLaneChangePath(debug_valid_path, "lane_change_valid_paths"));
338-
add(showFilteredObjects(
339-
debug_filtered_objects.current_lane, debug_filtered_objects.target_lane,
340-
debug_filtered_objects.other_lane, "object_filtered"));
341-
if (!debug_data.empty()) {
342-
add(showSafetyCheckInfo(debug_data, "object_debug_info"));
343-
add(showPredictedPath(debug_data, "ego_predicted_path"));
344-
add(showPolygon(debug_data, "ego_and_target_polygon_relation"));
345-
}
346-
347-
if (!debug_after_approval.empty()) {
348-
add(showSafetyCheckInfo(debug_after_approval, "object_debug_info_after_approval"));
349-
add(showPredictedPath(debug_after_approval, "ego_predicted_path_after_approval"));
350-
add(showPolygon(debug_after_approval, "ego_and_target_polygon_relation_after_approval"));
351-
}
324+
using marker_utils::lane_change_markers::createDebugMarkerArray;
325+
debug_marker_ = createDebugMarkerArray(module_type_->getDebugData());
352326
}
353327

354328
MarkerArray LaneChangeInterface::getModuleVirtualWall()

planning/behavior_path_lane_change_module/src/scene.cpp

+19-21
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
9797
lane_change_parameters_->rss_params_for_stuck, is_stuck);
9898
}
9999

100-
debug_valid_path_ = valid_paths;
100+
lane_change_debug_.valid_paths = valid_paths;
101101

102102
if (valid_paths.empty()) {
103103
safe_path.info.current_lanes = current_lanes;
@@ -421,13 +421,8 @@ void NormalLaneChange::resetParameters()
421421
current_lane_change_state_ = LaneChangeStates::Normal;
422422
abort_path_ = nullptr;
423423
status_ = {};
424+
lane_change_debug_.reset();
424425

425-
object_debug_.clear();
426-
object_debug_after_approval_.clear();
427-
debug_filtered_objects_.current_lane.clear();
428-
debug_filtered_objects_.target_lane.clear();
429-
debug_filtered_objects_.other_lane.clear();
430-
debug_valid_path_.clear();
431426
RCLCPP_DEBUG(logger_, "reset all flags and debug information.");
432427
}
433428

@@ -1112,7 +1107,7 @@ bool NormalLaneChange::getLaneChangePaths(
11121107
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
11131108
const bool check_safety) const
11141109
{
1115-
object_debug_.clear();
1110+
lane_change_debug_.collision_check_objects.clear();
11161111
if (current_lanes.empty() || target_lanes.empty()) {
11171112
RCLCPP_WARN(logger_, "target_neighbor_preferred_lane_poly_2d is empty. Not expected.");
11181113
return false;
@@ -1158,7 +1153,7 @@ bool NormalLaneChange::getLaneChangePaths(
11581153
}
11591154

11601155
const auto target_objects = getTargetObjects(current_lanes, target_lanes);
1161-
debug_filtered_objects_ = target_objects;
1156+
lane_change_debug_.filtered_objects = target_objects;
11621157

11631158
const auto prepare_durations = calcPrepareDuration(current_lanes, target_lanes);
11641159

@@ -1385,9 +1380,10 @@ bool NormalLaneChange::getLaneChangePaths(
13851380
std::vector<ExtendedPredictedObject> filtered_objects =
13861381
filterObjectsInTargetLane(target_objects, target_lanes);
13871382
if (
1388-
!is_stuck && utils::lane_change::passParkedObject(
1389-
route_handler, *candidate_path, filtered_objects, lane_change_buffer,
1390-
is_goal_in_route, *lane_change_parameters_, object_debug_)) {
1383+
!is_stuck &&
1384+
utils::lane_change::passParkedObject(
1385+
route_handler, *candidate_path, filtered_objects, lane_change_buffer, is_goal_in_route,
1386+
*lane_change_parameters_, lane_change_debug_.collision_check_objects)) {
13911387
debug_print(
13921388
"Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip "
13931389
"lane change.");
@@ -1400,7 +1396,8 @@ bool NormalLaneChange::getLaneChangePaths(
14001396
}
14011397

14021398
const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe(
1403-
*candidate_path, target_objects, rss_params, is_stuck, object_debug_);
1399+
*candidate_path, target_objects, rss_params, is_stuck,
1400+
lane_change_debug_.collision_check_objects);
14041401

14051402
if (is_safe) {
14061403
debug_print("ACCEPT!!!: it is valid and safe!");
@@ -1423,24 +1420,25 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14231420
const auto & target_lanes = status_.target_lanes;
14241421

14251422
const auto target_objects = getTargetObjects(current_lanes, target_lanes);
1426-
debug_filtered_objects_ = target_objects;
1423+
lane_change_debug_.filtered_objects = target_objects;
14271424

14281425
CollisionCheckDebugMap debug_data;
14291426
const bool is_stuck = isVehicleStuck(current_lanes);
14301427
const auto safety_status = isLaneChangePathSafe(
14311428
path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data);
14321429
{
14331430
// only for debug purpose
1434-
object_debug_.clear();
1435-
object_debug_lifetime_ += (stop_watch_.toc(getModuleTypeStr()) / 1000);
1436-
if (object_debug_lifetime_ > 2.0) {
1431+
lane_change_debug_.collision_check_objects.clear();
1432+
lane_change_debug_.collision_check_object_debug_lifetime +=
1433+
(stop_watch_.toc(getModuleTypeStr()) / 1000);
1434+
if (lane_change_debug_.collision_check_object_debug_lifetime > 2.0) {
14371435
stop_watch_.toc(getModuleTypeStr(), true);
1438-
object_debug_lifetime_ = 0.0;
1439-
object_debug_after_approval_.clear();
1436+
lane_change_debug_.collision_check_object_debug_lifetime = 0.0;
1437+
lane_change_debug_.collision_check_objects_after_approval.clear();
14401438
}
14411439

14421440
if (!safety_status.is_safe) {
1443-
object_debug_after_approval_ = debug_data;
1441+
lane_change_debug_.collision_check_objects_after_approval = debug_data;
14441442
}
14451443
}
14461444

@@ -1802,7 +1800,7 @@ bool NormalLaneChange::isVehicleStuck(
18021800
using lanelet::utils::getArcCoordinates;
18031801
const auto base_distance = getArcCoordinates(current_lanes, getEgoPose()).length;
18041802

1805-
for (const auto & object : debug_filtered_objects_.current_lane) {
1803+
for (const auto & object : lane_change_debug_.filtered_objects.current_lane) {
18061804
const auto & p = object.initial_pose.pose; // TODO(Horibe): consider footprint point
18071805

18081806
// Note: it needs chattering prevention.

planning/behavior_path_lane_change_module/src/utils/markers.cpp

+44
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
2323
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
2424
#include <visualization_msgs/msg/detail/marker__struct.hpp>
25+
#include <visualization_msgs/msg/detail/marker_array__struct.hpp>
2526

2627
#include <cstdint>
2728
#include <cstdlib>
@@ -120,4 +121,47 @@ MarkerArray showFilteredObjects(
120121
marker_array.markers.end(), other_marker.markers.begin(), other_marker.markers.end());
121122
return marker_array;
122123
}
124+
125+
MarkerArray createDebugMarkerArray(const Debug & debug_data)
126+
{
127+
using marker_utils::showPolygon;
128+
using marker_utils::showPredictedPath;
129+
using marker_utils::showSafetyCheckInfo;
130+
using marker_utils::lane_change_markers::showAllValidLaneChangePath;
131+
using marker_utils::lane_change_markers::showFilteredObjects;
132+
133+
const auto & debug_collision_check_object = debug_data.collision_check_objects;
134+
const auto & debug_collision_check_object_after_approval =
135+
debug_data.collision_check_objects_after_approval;
136+
const auto & debug_valid_paths = debug_data.valid_paths;
137+
const auto & debug_filtered_objects = debug_data.filtered_objects;
138+
139+
MarkerArray debug_marker;
140+
const auto add = [&debug_marker](const MarkerArray & added) {
141+
tier4_autoware_utils::appendMarkerArray(added, &debug_marker);
142+
};
143+
144+
add(showAllValidLaneChangePath(debug_valid_paths, "lane_change_valid_paths"));
145+
add(showFilteredObjects(
146+
debug_filtered_objects.current_lane, debug_filtered_objects.target_lane,
147+
debug_filtered_objects.other_lane, "object_filtered"));
148+
149+
if (!debug_collision_check_object.empty()) {
150+
add(showSafetyCheckInfo(debug_collision_check_object, "collision_check_object_info"));
151+
add(showPredictedPath(debug_collision_check_object, "ego_predicted_path"));
152+
add(showPolygon(debug_collision_check_object, "ego_and_target_polygon_relation"));
153+
}
154+
155+
if (!debug_collision_check_object_after_approval.empty()) {
156+
add(showSafetyCheckInfo(
157+
debug_collision_check_object_after_approval, "object_debug_info_after_approval"));
158+
add(showPredictedPath(
159+
debug_collision_check_object_after_approval, "ego_predicted_path_after_approval"));
160+
add(showPolygon(
161+
debug_collision_check_object_after_approval,
162+
"ego_and_target_polygon_relation_after_approval"));
163+
}
164+
165+
return debug_marker;
166+
}
123167
} // namespace marker_utils::lane_change_markers

0 commit comments

Comments
 (0)