Skip to content

Commit

Permalink
fix(behavior_path_planner): fix offset calculation for turn signal in…
Browse files Browse the repository at this point in the history
… start_planner (autowarefoundation#3945)

Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp>
  • Loading branch information
tkimura4 authored Jun 12, 2023
1 parent 90b9f07 commit 07f8de7
Showing 1 changed file with 8 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -796,7 +796,14 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const
// pull out path does not overlap
const double distance_from_end =
motion_utils::calcSignedArcLength(path.points, end_pose.position, current_pose.position);
const double lateral_offset = inverseTransformPoint(end_pose.position, start_pose).y;

if (path.points.empty()) {
return {};
}
const auto closest_idx = motion_utils::findNearestIndex(path.points, start_pose.position);
const auto lane_id = path.points.at(closest_idx).lane_ids.front();
const auto lane = planner_data_->route_handler->getLaneletMapPtr()->laneletLayer.get(lane_id);
const double lateral_offset = lanelet::utils::getLateralDistanceToCenterline(lane, start_pose);

if (distance_from_end < 0.0 && lateral_offset > parameters_->th_blinker_on_lateral_offset) {
turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
Expand Down

0 comments on commit 07f8de7

Please sign in to comment.