Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(avoidance): turn off blinker when the ego return original lane #6300

Merged
merged 4 commits into from
Feb 27, 2024

Conversation

satoshi-ota
Copy link
Contributor

@satoshi-ota satoshi-ota commented Feb 5, 2024

Description

Previously, avoidance module continued to turn on blinker until the ego returned original path completely. Sometimes, the module keeped turn signal even when the ego stopped in front of intersection due to red traffic light. However, the signal maybe causes misunderstanding that the ego is going to turn left or right at the intersection.

In this PR, I fixed turn signal calculation logic in order to disable turn signal if the ego stopped in original lane.

simplescreenrecorder-2024-02-05_10.59.41.mp4

Tests performed

Effects on system behavior

Nothing.

Pre-review checklist for the PR author

The PR author must check the checkboxes below when creating the PR.

In-review checklist for the PR reviewers

The PR reviewers must check the checkboxes below before approval.

Post-review checklist for the PR author

The PR author must check the checkboxes below before merging.

  • There are no open discussions or they are tracked via tickets.

After all checkboxes are checked, anyone who has write access can merge the PR.

@github-actions github-actions bot added the component:planning Route planning, decision-making, and navigation. (auto-assigned) label Feb 5, 2024
@satoshi-ota satoshi-ota marked this pull request as ready for review February 5, 2024 03:06
Copy link

codecov bot commented Feb 5, 2024

Codecov Report

Attention: Patch coverage is 0% with 35 lines in your changes are missing coverage. Please review.

Project coverage is 14.64%. Comparing base (8e45709) to head (2114b0e).
Report is 5 commits behind head on main.

Files Patch % Lines
...nning/behavior_path_avoidance_module/src/utils.cpp 0.00% 26 Missing ⚠️
...nning/behavior_path_avoidance_module/src/scene.cpp 0.00% 8 Missing ⚠️
...planner_common/utils/path_shifter/path_shifter.hpp 0.00% 1 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main    #6300      +/-   ##
==========================================
- Coverage   14.64%   14.64%   -0.01%     
==========================================
  Files        1899     1899              
  Lines      130283   130303      +20     
  Branches    38311    38324      +13     
==========================================
+ Hits        19082    19083       +1     
- Misses      89785    89802      +17     
- Partials    21416    21418       +2     
Flag Coverage Δ *Carryforward flag
differential 11.01% <0.00%> (?)
total 14.64% <ø> (+<0.01%) ⬆️ Carriedforward from 8e45709

*This pull request uses carry forward flags. Click here to find out more.

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

@@ -250,16 +250,37 @@ void pushUniqueVector(T & base_vector, const T & additional_vector)
base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end());
}

bool isAvoidShift(const double start_shift_length, const double end_shift_length)
{
constexpr double THRESHOLD = 0.1;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

bool isAvoidShift(const double start_shift_length, const double end_shift_length, const double THRESHOLD = 0.1)
{
  return std::abs(start_shift_length) < THRESHOLD && std::abs(end_shift_length) > THRESHOLD;
}

Personally, I would wonder if it is helpful to make threshold a "default" argument for these functions?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed in e677db4.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you. I have no further questions now.

@@ -2286,7 +2324,7 @@ double calcDistanceToReturnDeadLine(
return distance_to_return_dead_line;
}

TurnSignalInfo calcTurnSignalInfo(
std::pair<TurnSignalInfo, bool> calcTurnSignalInfo(
Copy link
Contributor

@Owen-Liuyuxuan Owen-Liuyuxuan Feb 20, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the refactoring.
Personally, with the current change, I would suggest renaming this THRESHOLD into something like current_shift_threshold because it is no longer a "general" threshold in this calcTurnSignalInfo function.
(I am not familiar with the extra influences of renaming this parameter, so it is just a small idea on readability)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed in e677db4.

Copy link
Contributor

@shmpwk shmpwk left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Aside from Liu-san comments, LGTM

Comment on lines 346 to 352
for (const auto & lane : original_lanes) {
if (within(to2D(toLaneletPoint(ego_pos)), lane.polygon2d().basicPolygon())) {
return true;
}
}

return false;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

personally I would suggest std::any_of for this part.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed in a52553a.

@satoshi-ota satoshi-ota added the run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Feb 26, 2024
@satoshi-ota satoshi-ota merged commit 4b784b4 into autowarefoundation:main Feb 27, 2024
28 of 32 checks passed
@satoshi-ota satoshi-ota deleted the fix/turn-signal branch February 27, 2024 05:30
StepTurtle pushed a commit to StepTurtle/autoware.universe that referenced this pull request Feb 28, 2024
…utowarefoundation#6300)

* refactor(path_shifter): add id to ShiftLine

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): turn off blinker when the ego return original lane

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use threshold param

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use lambda

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
HansRobo pushed a commit that referenced this pull request Mar 12, 2024
…6300)

* refactor(path_shifter): add id to ShiftLine

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): turn off blinker when the ego return original lane

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use threshold param

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use lambda

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
Signed-off-by: Kotaro Yoshimoto <[email protected]>
karishma1911 pushed a commit to Interplai/autoware.universe that referenced this pull request Jun 3, 2024
…utowarefoundation#6300)

* refactor(path_shifter): add id to ShiftLine

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): turn off blinker when the ego return original lane

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use threshold param

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use lambda

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
satoshi-ota added a commit to tier4/autoware.universe that referenced this pull request Jun 6, 2024
…utowarefoundation#6300)

* refactor(path_shifter): add id to ShiftLine

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): turn off blinker when the ego return original lane

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use threshold param

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): use lambda

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:planning Route planning, decision-making, and navigation. (auto-assigned) run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants