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

refactor(lane_change): add new structs (TransientData) to store commonly used values #8849

Open
wants to merge 18 commits into
base: main
Choose a base branch
from

Conversation

zulfaqar-azmi-t4
Copy link
Contributor

@zulfaqar-azmi-t4 zulfaqar-azmi-t4 commented Sep 11, 2024

Description

This PR adds TransientData to standardize commonly used values in the lane change module, such as the current lanes' buffer and the distance to the terminal start and end. The goal is to ensure consistency when calculating limits and lengths.

Related links

Parent Issue:

  • None

How was this PR tested?

  1. Build complete
  2. PSIM
  3. Scenario Test TBD

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

@github-actions github-actions bot added type:documentation Creating or refining documentation. (auto-assigned) component:planning Route planning, decision-making, and navigation. (auto-assigned) labels Sep 11, 2024
Copy link

github-actions bot commented Sep 11, 2024

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

@zulfaqar-azmi-t4 zulfaqar-azmi-t4 force-pushed the lc-rename-min-lc-length-to-buffer branch 4 times, most recently from 574f9c0 to d51d847 Compare September 19, 2024 01:46
@github-actions github-actions bot removed the type:documentation Creating or refining documentation. (auto-assigned) label Sep 19, 2024
@zulfaqar-azmi-t4 zulfaqar-azmi-t4 changed the title Lc rename min lc length to buffer refactor(lane_change): add new structs (TransientData) to store commonly used values Sep 19, 2024
@zulfaqar-azmi-t4 zulfaqar-azmi-t4 marked this pull request as ready for review September 19, 2024 02:55
if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) {
if (
lane_changing_length + prepare_length +
common_data_ptr_->transient_data.next_lc_buffer.min >
Copy link
Contributor

Choose a reason for hiding this comment

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

Just curious why did you add the next LC buffer here?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I'm making an assumption that we want to do more than 1 lane changes. This is assuming that the end point of current and target lane align with each other.

Additional note: some additional fix is needed if the end point is not aligned.

Copy link
Contributor

@mkquda mkquda Sep 19, 2024

Choose a reason for hiding this comment

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

but isn't this covered by the check here

Comment on lines +278 to +281
const auto lc_length_and_dist_buffer =
utils::lane_change::calculation::calc_lc_length_and_dist_buffer(
common_data_ptr_, get_current_lanes());
return std::get<1>(lc_length_and_dist_buffer).min;
Copy link
Contributor

Choose a reason for hiding this comment

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

(minor) I think you can do something like this which is a bit easier to read.

Suggested change
const auto lc_length_and_dist_buffer =
utils::lane_change::calculation::calc_lc_length_and_dist_buffer(
common_data_ptr_, get_current_lanes());
return std::get<1>(lc_length_and_dist_buffer).min;
const auto [_, dist_buffer] =
utils::lane_change::calculation::calc_lc_length_and_dist_buffer(
common_data_ptr_, get_current_lanes());
return dist_buffer.min;

const auto current_lanes = get_current_lanes();
if (current_lanes.empty()) {
RCLCPP_DEBUG(logger_, "no empty lanes");
return std::numeric_limits<double>::infinity();
Copy link
Contributor

Choose a reason for hiding this comment

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

If I understand the code correctly, the new return value in case current_lanes is empty is 0 compared to infinity() previously. Is this okay ?

  • the calc_lc_length_and_dist_buffer() returns {} when lanes is empty.
  • {} uses the default constructor of pair which uses the default constructor of Boundary which sets min = 0.0.

Comment on lines +116 to +118
const auto acc_boundary = calcCurrentMinMaxAcceleration();
transient_data.acc.min = std::get<0>(acc_boundary);
transient_data.acc.max = std::get<1>(acc_boundary);
Copy link
Contributor

Choose a reason for hiding this comment

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

I think you can do something like that:

Suggested change
const auto acc_boundary = calcCurrentMinMaxAcceleration();
transient_data.acc.min = std::get<0>(acc_boundary);
transient_data.acc.max = std::get<1>(acc_boundary);
std::tie(transient_data.acc.min, transient_data.acc.max) = calcCurrentMinMaxAcceleration();

or are they the same type ? In which case:

Suggested change
const auto acc_boundary = calcCurrentMinMaxAcceleration();
transient_data.acc.min = std::get<0>(acc_boundary);
transient_data.acc.max = std::get<1>(acc_boundary);
transient_data = calcCurrentMinMaxAcceleration();

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
zulfaqar-azmi-t4 and others added 14 commits September 24, 2024 15:26
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Zulfaqar Azmi <[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)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants