-
Notifications
You must be signed in to change notification settings - Fork 650
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(behavior_velocity_planner): consider all the lane ids in path #1630
fix(behavior_velocity_planner): consider all the lane ids in path #1630
Conversation
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
ff007a5
to
a236d44
Compare
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
if (last_itr.base() != path.points.end()) { | ||
const auto & next_lanelet = | ||
lanelet_map_ptr->laneletLayer.get((*last_itr.base()).lane_ids.front()); | ||
const auto & next_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); | ||
ego_lane_with_next_lane = {assigned_lanelet, next_lanelet}; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Is this change OK? @soblin
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
You do not need to change L683-684 because last_itr
should still be the last PathWithPointWithLaneId
that contains lane_id_
in it. Just FYI, last_itr.base() returns its next element.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Okay, I reverted.
9c99e64
@taikitanaka3 @soblin Could you review this |
planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp
Show resolved
Hide resolved
Codecov Report
@@ Coverage Diff @@
## main #1630 +/- ##
==========================================
- Coverage 10.77% 10.69% -0.08%
==========================================
Files 1111 1111
Lines 78530 79787 +1257
Branches 18554 19374 +820
==========================================
+ Hits 8464 8537 +73
- Misses 61206 62301 +1095
- Partials 8860 8949 +89
*This pull request uses carry forward flags. Click here to find out more.
Help us with your feedback. Take ten seconds to tell us how you rate us. Have a feature suggestion? Share it here. |
return true; | ||
} | ||
} | ||
return false; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
return std::find(p.lane_ids.begin(), p.lane_ids.end(), lane_id_) != p.lane_ids.end()
?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
You're right. It's much better. Thanks.
9c99e64
…er4#1630) * fix(behavior_velocity_planner): consider all the lane ids in path Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove obsolete comment Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
…er4#1630) * fix(behavior_velocity_planner): consider all the lane ids in path Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove obsolete comment Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
…er4#1630) * fix(behavior_velocity_planner): consider all the lane ids in path Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove obsolete comment Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
…towarefoundation#1630) * fix(behavior_velocity_planner): consider all the lane ids in path Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove obsolete comment Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
…er4#1630) * fix(behavior_velocity_planner): consider all the lane ids in path Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove obsolete comment Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: Takayuki Murooka takayuki5168@gmail.com
Description
With this PR, the path point sometimes has more than 2 lane_ids which cannot be dealt with in some behavior_velocity_planner's module.
#1626
So I fixed behavior_velocity_planner to consider all the lane ids in the path from behavior_path_planner.
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.
After all checkboxes are checked, anyone who has write access can merge the PR.