Skip to content

Commit 4d7d70b

Browse files
Fixed turn_indicator_batch_idx
Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
1 parent dd858eb commit 4d7d70b

File tree

1 file changed

+6
-3
lines changed

1 file changed

+6
-3
lines changed

planning/autoware_diffusion_planner/src/diffusion_planner_core.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -345,13 +345,16 @@ PlannerOutput DiffusionPlannerCore::create_planner_output(
345345
agent_poses, frame_context.ego_centric_neighbor_histories, timestamp, batch_idx);
346346

347347
// TurnIndicatorsCommand
348-
// TODO(sakoda): Use the first logit as the main turn indicator command.
349-
// There may be bugs in the current implementation.
348+
// Use the first batch's logit as the main turn indicator command.
349+
constexpr int64_t turn_indicator_batch_idx = 0;
350+
const std::vector<float> first_turn_indicator_logit(
351+
turn_indicator_logit.begin() + TURN_INDICATOR_OUTPUT_DIM * turn_indicator_batch_idx,
352+
turn_indicator_logit.begin() + TURN_INDICATOR_OUTPUT_DIM * (turn_indicator_batch_idx + 1));
350353
const int64_t prev_report = turn_indicators_history_.empty()
351354
? TurnIndicatorsReport::DISABLE
352355
: turn_indicators_history_.back().report;
353356
output.turn_indicator_command =
354-
turn_indicator_manager_.evaluate(turn_indicator_logit, timestamp, prev_report);
357+
turn_indicator_manager_.evaluate(first_turn_indicator_logit, timestamp, prev_report);
355358

356359
return output;
357360
}

0 commit comments

Comments
 (0)