Skip to content

Commit 267c6b2

Browse files
committed
feat: output avoidance debug array whenever the avoidance module is enabled (autowarefoundation#835)
Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp>
1 parent 552a7d1 commit 267c6b2

File tree

3 files changed

+11
-22
lines changed

3 files changed

+11
-22
lines changed

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

+1-2
Original file line numberDiff line numberDiff line change
@@ -157,8 +157,7 @@ class AvoidanceModule : public SceneModuleInterface
157157
// debug
158158
mutable DebugData debug_data_;
159159
void setDebugData(const PathShifter & shifter, const DebugData & debug);
160-
mutable std::vector<AvoidanceDebugMsg> debug_avoidance_initializer_for_object;
161-
mutable std::vector<AvoidanceDebugMsg> debug_avoidance_initializer_for_shift_point;
160+
mutable std::vector<AvoidanceDebugMsg> debug_avoidance_initializer_for_shift_point_;
162161
// =====================================
163162
// ========= helper functions ==========
164163
// =====================================

planning/behavior_path_planner/src/behavior_tree_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,7 @@ AvoidanceDebugMsgArray BehaviorTreeManager::getAvoidanceDebugMsgArray()
129129
const auto avoidance_module = std::find_if(
130130
scene_modules_.begin(), scene_modules_.end(),
131131
[](const std::shared_ptr<SceneModuleInterface> & module_ptr) {
132-
return module_ptr->current_state_ == BT::NodeStatus::SUCCESS;
132+
return module_ptr->name() == "Avoidance";
133133
});
134134
if (avoidance_module != scene_modules_.end()) {
135135
const auto & ptr = avoidance_module->get()->getAvoidanceDebugMsgArray();

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

+9-19
Original file line numberDiff line numberDiff line change
@@ -77,8 +77,6 @@ bool AvoidanceModule::isExecutionReady() const
7777
{
7878
DebugData debug;
7979
static_cast<void>(calcAvoidancePlanningData(debug));
80-
debug_avoidance_msg_array_ptr_ =
81-
std::make_shared<AvoidanceDebugMsgArray>(debug.avoidance_debug_msg_array);
8280
}
8381

8482
if (current_state_ == BT::NodeStatus::RUNNING) {
@@ -95,8 +93,6 @@ BT::NodeStatus AvoidanceModule::updateState()
9593
DebugData debug;
9694
const auto avoid_data = calcAvoidancePlanningData(debug);
9795
const bool has_avoidance_target = !avoid_data.objects.empty();
98-
debug_avoidance_msg_array_ptr_ =
99-
std::make_shared<AvoidanceDebugMsgArray>(debug.avoidance_debug_msg_array);
10096
if (!is_plan_running && !has_avoidance_target) {
10197
current_state_ = BT::NodeStatus::SUCCESS;
10298
} else {
@@ -313,8 +309,13 @@ ObjectDataArray AvoidanceModule::calcAvoidanceTargetObjects(
313309

314310
// debug
315311
{
316-
debug_avoidance_initializer_for_object = avoidance_debug_msg_array;
317-
debug.avoidance_debug_msg_array.avoidance_info = std::move(avoidance_debug_msg_array);
312+
auto & debug_data_avoidance = debug_data_.avoidance_debug_msg_array.avoidance_info;
313+
debug_data_avoidance = avoidance_debug_msg_array;
314+
debug_data_avoidance.insert(
315+
debug_data_avoidance.end(), debug_avoidance_initializer_for_shift_point_.begin(),
316+
debug_avoidance_initializer_for_shift_point_.end());
317+
debug_avoidance_msg_array_ptr_ =
318+
std::make_shared<AvoidanceDebugMsgArray>(debug_data_.avoidance_debug_msg_array);
318319
debug.farthest_linestring_from_overhang =
319320
std::make_shared<lanelet::ConstLineStrings3d>(debug_linestring);
320321
debug.current_lanelets = std::make_shared<lanelet::ConstLanelets>(current_lanes);
@@ -610,14 +611,7 @@ AvoidPointArray AvoidanceModule::calcRawShiftPointsFromObjects(
610611
avoidance_debug_msg_array.push_back(avoidance_debug_msg);
611612
}
612613

613-
{
614-
debug_avoidance_initializer_for_shift_point = std::move(avoidance_debug_msg_array);
615-
auto & debug_data_avoidance = debug_data_.avoidance_debug_msg_array.avoidance_info;
616-
debug_data_avoidance = debug_avoidance_initializer_for_object;
617-
debug_data_avoidance.insert(
618-
debug_data_avoidance.end(), debug_avoidance_initializer_for_shift_point.begin(),
619-
debug_avoidance_initializer_for_shift_point.end());
620-
}
614+
debug_avoidance_initializer_for_shift_point_ = std::move(avoidance_debug_msg_array);
621615
fillAdditionalInfoFromLongitudinal(avoid_points);
622616

623617
return avoid_points;
@@ -2207,8 +2201,6 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval()
22072201
// we can execute the plan() since it handles the approval appropriately.
22082202
BehaviorModuleOutput out = plan();
22092203
out.path_candidate = std::make_shared<PathWithLaneId>(planCandidate());
2210-
debug_avoidance_msg_array_ptr_ =
2211-
std::make_shared<AvoidanceDebugMsgArray>(debug_data_.avoidance_debug_msg_array);
22122204
return out;
22132205
}
22142206

@@ -2433,9 +2425,6 @@ void AvoidanceModule::updateData()
24332425
{
24342426
debug_data_ = DebugData();
24352427
avoidance_data_ = calcAvoidancePlanningData(debug_data_);
2436-
const auto avoidance_debug_msgs = debug_data_.avoidance_debug_msg_array.avoidance_info;
2437-
debug_avoidance_msg_array_ptr_ =
2438-
std::make_shared<AvoidanceDebugMsgArray>(debug_data_.avoidance_debug_msg_array);
24392428

24402429
// TODO(Horibe): this is not tested yet, disable now.
24412430
updateRegisteredObject(avoidance_data_.objects);
@@ -2583,6 +2572,7 @@ void AvoidanceModule::initVariables()
25832572
path_shifter_ = PathShifter{};
25842573

25852574
debug_avoidance_msg_array_ptr_.reset();
2575+
debug_avoidance_initializer_for_shift_point_.clear();
25862576
debug_data_ = DebugData();
25872577

25882578
registered_raw_shift_points_ = {};

0 commit comments

Comments
 (0)