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

feat(crosswalk): dyanmic timeout for no intention to walk decision #5188

Conversation

takayuki5168
Copy link
Contributor

@takayuki5168 takayuki5168 commented Oct 1, 2023

Description

Currently, the timeout parameter to decide if the pedestrian has the intention to walk to the crosswalk is constant.
In order not to be too conservative, this parameter should depend on the distance from the pedestrian to the crosswalk.
This PR implements the feature.

Tests performed

psim
scenario sim: https://evaluation.tier4.jp/evaluation/reports/18915c07-9a27-5ffc-8a34-5394fd2b4f2b?project_id=prd_jt

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.

Comment on lines +79 to +104
double InterpolateMap(
const std::vector<double> & key_map, const std::vector<double> & value_map, const double query)
{
// If the speed is out of range of the key_map, apply zero-order hold.
if (query <= key_map.front()) {
return value_map.front();
}
if (query >= key_map.back()) {
return value_map.back();
}

// Apply linear interpolation
for (size_t i = 0; i < key_map.size() - 1; ++i) {
if (key_map.at(i) <= query && query <= key_map.at(i + 1)) {
auto ratio = (query - key_map.at(i)) / std::max(key_map.at(i + 1) - key_map.at(i), 1.0e-5);
ratio = std::clamp(ratio, 0.0, 1.0);
const auto interp = value_map.at(i) + ratio * (value_map.at(i + 1) - value_map.at(i));
return interp;
}
}

std::cerr << "Crosswalk's InterpolateMap interpolation logic is broken."
"Please check the code."
<< std::endl;
return value_map.back();
}
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Copied from here

VectorXd MPC::calcSteerRateLimitOnTrajectory(
const MPCTrajectory & trajectory, const double current_velocity) const
{
const auto interp = [&](const auto & steer_rate_limit_map, const auto & current) {
std::vector<double> reference, limits;
for (const auto & p : steer_rate_limit_map) {
reference.push_back(p.first);
limits.push_back(p.second);
}
// If the speed is out of range of the reference, apply zero-order hold.
if (current <= reference.front()) {
return limits.front();
}
if (current >= reference.back()) {
return limits.back();
}
// Apply linear interpolation
for (size_t i = 0; i < reference.size() - 1; ++i) {
if (reference.at(i) <= current && current <= reference.at(i + 1)) {
auto ratio =
(current - reference.at(i)) / std::max(reference.at(i + 1) - reference.at(i), 1.0e-5);
ratio = std::clamp(ratio, 0.0, 1.0);
const auto interp = limits.at(i) + ratio * (limits.at(i + 1) - limits.at(i));
return interp;
}
}
std::cerr << "MPC::calcSteerRateLimitOnTrajectory() interpolation logic is broken. Command "
"filter is not working. Please check the code."
<< std::endl;
return reference.back();
};

@takayuki5168 takayuki5168 marked this pull request as ready for review October 1, 2023 15:52
@takayuki5168 takayuki5168 added the run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Oct 1, 2023
@codecov
Copy link

codecov bot commented Oct 1, 2023

Codecov Report

Attention: 21 lines in your changes are missing coverage. Please review.

Comparison is base (93b6118) 14.77% compared to head (1e81da2) 14.77%.
Report is 3 commits behind head on main.

Additional details and impacted files
@@            Coverage Diff             @@
##             main    #5188      +/-   ##
==========================================
- Coverage   14.77%   14.77%   -0.01%     
==========================================
  Files        1636     1636              
  Lines      113635   113649      +14     
  Branches    34932    34940       +8     
==========================================
  Hits        16793    16793              
- Misses      78001    78013      +12     
- Partials    18841    18843       +2     
Flag Coverage Δ *Carryforward flag
differential 9.41% <0.00%> (?)
total 14.77% <ø> (+<0.01%) ⬆️ Carriedforward from 93b6118

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

Files Coverage Δ
...er/src/scene_module/avoidance/avoidance_module.cpp 12.33% <ø> (+<0.01%) ⬆️
...em_monitor/src/process_monitor/process_monitor.cpp 0.00% <ø> (ø)
..._velocity_crosswalk_module/src/scene_crosswalk.cpp 0.00% <0.00%> (ø)
...behavior_velocity_crosswalk_module/src/manager.cpp 7.92% <0.00%> (-0.17%) ⬇️
..._velocity_crosswalk_module/src/scene_crosswalk.hpp 0.00% <0.00%> (ø)

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

@takayuki5168 takayuki5168 force-pushed the feat/crosswalk-dynamic-timeout-for-no-intention-to-walk branch from 7da6bec to 67c3962 Compare October 2, 2023 00:14
Copy link
Contributor

@satoshi-ota satoshi-ota left a comment

Choose a reason for hiding this comment

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

LGTM

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
@takayuki5168 takayuki5168 force-pushed the feat/crosswalk-dynamic-timeout-for-no-intention-to-walk branch from 67c3962 to 1e81da2 Compare October 2, 2023 10:09
@takayuki5168 takayuki5168 merged commit 8ab910b into autowarefoundation:main Oct 3, 2023
@takayuki5168 takayuki5168 deleted the feat/crosswalk-dynamic-timeout-for-no-intention-to-walk branch October 3, 2023 03:11
takayuki5168 added a commit to tier4/autoware.universe that referenced this pull request Oct 3, 2023
…utowarefoundation#5188)

* feat(crosswalk): dyanmic timeout for no intention to walk decision

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* update config

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* update

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* update config

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

---------

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
takayuki5168 added a commit to tier4/autoware.universe that referenced this pull request Oct 4, 2023
…utowarefoundation#5188) (#902)

feat(crosswalk): dyanmic timeout for no intention to walk decision (autowarefoundation#5188)

* feat(crosswalk): dyanmic timeout for no intention to walk decision



* update config



* update



* update config



---------

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
t4-x2 pushed a commit to tier4/autoware.universe that referenced this pull request Oct 5, 2023
…utowarefoundation#5188) (#902)

feat(crosswalk): dyanmic timeout for no intention to walk decision (autowarefoundation#5188)

* feat(crosswalk): dyanmic timeout for no intention to walk decision



* update config



* update



* update config



---------

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
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.

2 participants