Skip to content

Commit

Permalink
feat(lane_change): reduce prepare duration when blinker has been acti…
Browse files Browse the repository at this point in the history
…vated (autowarefoundation#9185)

* add minimum prepare duration parameter

Signed-off-by: mohammad alqudah <[email protected]>

* reduce prepare duration according to signal activation time

Signed-off-by: mohammad alqudah <[email protected]>

* chore: update CODEOWNERS (autowarefoundation#9203)

Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
Co-authored-by: github-actions <[email protected]>

* refactor(time_utils): prefix package and namespace with autoware (autowarefoundation#9173)

* refactor(time_utils): prefix package and namespace with autoware

Signed-off-by: Esteve Fernandez <[email protected]>

* refactor(time_utils): prefix package and namespace with autoware

Signed-off-by: Esteve Fernandez <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: Esteve Fernandez <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

* feat(rtc_interface): add requested field (autowarefoundation#9202)

* add requested feature

Signed-off-by: Go Sakayori <[email protected]>

* Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp

Co-authored-by: Satoshi OTA <[email protected]>

---------

Signed-off-by: Go Sakayori <[email protected]>
Co-authored-by: Satoshi OTA <[email protected]>

* fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (autowarefoundation#9199)

Signed-off-by: Maxime CLEMENT <[email protected]>

* fix(bpp): prevent accessing nullopt (autowarefoundation#9204)

fix(bpp): calcDistanceToRedTrafficLight null

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (autowarefoundation#9201)

* refactor: grouping functions

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: grouping parameters

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: rename member road_users_history to road_users_history_

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: separate util functions

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: Add explicit template instantiation for removeOldObjectsHistory function

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: Add tf2_geometry_msgs to data_structure

Signed-off-by: Taekjin LEE <[email protected]>

* refactor: Remove unused variables and functions in map_based_prediction_node.cpp

Signed-off-by: Taekjin LEE <[email protected]>

* Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp

* Apply suggestions from code review

* style(pre-commit): autofix

---------

Signed-off-by: Taekjin LEE <[email protected]>
Co-authored-by: Mamoru Sobue <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

* refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (autowarefoundation#8912)

* Moved ndt_omp into ndt_scan_matcher

Signed-off-by: Shintaro Sakoda <[email protected]>

* Added Copyright

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed include

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed cast style

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed include

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed honorific title

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed honorific title

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed include hierarchy

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed include hierarchy

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed hierarchy

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed NVTP to NVTL

Signed-off-by: Shintaro Sakoda <[email protected]>

* Added cspell:ignore

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed miss spell

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed include

Signed-off-by: Shintaro Sakoda <[email protected]>

* Renamed applyFilter

Signed-off-by: Shintaro Sakoda <[email protected]>

* Moved ***_impl.hpp from include/ to src/

Signed-off-by: Shintaro Sakoda <[email protected]>

* style(pre-commit): autofix

* Fixed variable scope

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed to pass by reference

Signed-off-by: Shintaro Sakoda <[email protected]>

---------

Signed-off-by: Shintaro Sakoda <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

* feat(autoware_test_utils): add traffic light msgs parser (autowarefoundation#9177)

Signed-off-by: Mamoru Sobue <[email protected]>

* modify implementation to compute and keep actual prepare duration in transient data

Signed-off-by: mohammad alqudah <[email protected]>

* if LC path is approved, set prepare duration in transient data from approved path prepare duration

Signed-off-by: mohammad alqudah <[email protected]>

* change default value of LC param min_prepare_duration

Signed-off-by: mohammad alqudah <[email protected]>

* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

Co-authored-by: Zulfaqar Azmi <[email protected]>

* add function to set signal activation time, add docstring for function calc_actual_prepare_duration

Signed-off-by: mohammad alqudah <[email protected]>

* check for zero value max_acc to avoid division by zero

Signed-off-by: mohammad alqudah <[email protected]>

* chore: rename codeowners file

Signed-off-by: tomoya.kimura <[email protected]>

* chore: rename codeowners file

Signed-off-by: tomoya.kimura <[email protected]>

* chore: rename codeowners file

Signed-off-by: tomoya.kimura <[email protected]>

* allow decelerating in lane changing phase near terminal

Signed-off-by: mohammad alqudah <[email protected]>

* fix spelling

Signed-off-by: mohammad alqudah <[email protected]>

* fix units

Signed-off-by: mohammad alqudah <[email protected]>

* allow decelerating in lane changing phase near terminal

Signed-off-by: mohammad alqudah <[email protected]>

* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md

Co-authored-by: Maxime CLEMENT <[email protected]>

* run pre-commit check

Signed-off-by: mohammad alqudah <[email protected]>

* fix spelling

Signed-off-by: mohammad alqudah <[email protected]>

* fix format

Signed-off-by: mohammad alqudah <[email protected]>

* allow decelerating in lane changing phase near terminal

Signed-off-by: mohammad alqudah <[email protected]>

* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md

Co-authored-by: Maxime CLEMENT <[email protected]>

* run pre-commit check

Signed-off-by: mohammad alqudah <[email protected]>

* fix spelling

Signed-off-by: mohammad alqudah <[email protected]>

* fix format

Signed-off-by: mohammad alqudah <[email protected]>

---------

Signed-off-by: mohammad alqudah <[email protected]>
Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
Signed-off-by: Esteve Fernandez <[email protected]>
Signed-off-by: Go Sakayori <[email protected]>
Signed-off-by: Maxime CLEMENT <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>
Signed-off-by: Taekjin LEE <[email protected]>
Signed-off-by: Shintaro Sakoda <[email protected]>
Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: tomoya.kimura <[email protected]>
Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com>
Co-authored-by: github-actions <[email protected]>
Co-authored-by: Esteve Fernandez <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Go Sakayori <[email protected]>
Co-authored-by: Satoshi OTA <[email protected]>
Co-authored-by: Maxime CLEMENT <[email protected]>
Co-authored-by: Shumpei Wakabayashi <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>
Co-authored-by: Mamoru Sobue <[email protected]>
Co-authored-by: SakodaShintaro <[email protected]>
Co-authored-by: Zulfaqar Azmi <[email protected]>
Co-authored-by: tomoya.kimura <[email protected]>
  • Loading branch information
14 people authored Dec 5, 2024
1 parent 87e95bf commit 0992f1d
Show file tree
Hide file tree
Showing 13 changed files with 104 additions and 26 deletions.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -886,7 +886,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 |
| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 |
| `backward_length_from_intersection` | [m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 |
| `trajectory.prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 |
| `trajectory.max_prepare_duration` | [s] | double | The maximum preparation time for the ego vehicle to be ready to perform lane change. | 4.0 |
| `trajectory.min_prepare_duration` | [s] | double | The minimum preparation time for the ego vehicle to be ready to perform lane change. | 2.0 |
| `trajectory.lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 |
| `trajectory.minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 |
| `trajectory.lon_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@

# trajectory generation
trajectory:
prepare_duration: 4.0
max_prepare_duration: 4.0
min_prepare_duration: 2.0
lateral_jerk: 0.5
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class NormalLaneChange : public LaneChangeBase

void update_lanes(const bool is_approved) final;

void update_transient_data() final;
void update_transient_data(const bool is_approved) final;

void update_filtered_objects() final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class LaneChangeBase

virtual void update_lanes(const bool is_approved) = 0;

virtual void update_transient_data() = 0;
virtual void update_transient_data(const bool is_approved) = 0;

virtual void update_filtered_objects() = 0;

Expand Down Expand Up @@ -267,6 +267,15 @@ class LaneChangeBase
return turn_signal;
}

void set_signal_activation_time(const bool reset = false) const
{
if (reset) {
signal_activation_time_ = std::nullopt;
} else if (!signal_activation_time_) {
signal_activation_time_ = clock_.now();
}
}

LaneChangeStatus status_{};
PathShifter path_shifter_{};

Expand All @@ -292,6 +301,7 @@ class LaneChangeBase

mutable StopWatch<std::chrono::milliseconds> stop_watch_;
mutable lane_change::Debug lane_change_debug_;
mutable std::optional<rclcpp::Time> signal_activation_time_{std::nullopt};

rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr());
mutable rclcpp::Clock clock_{RCL_ROS_TIME};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ double calc_dist_to_last_fit_width(
* of the maximum lane change preparation duration and the maximum velocity of the ego vehicle.
*
* @param common_data_ptr Shared pointer to a CommonData structure, which should include:
* - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change
* - `lc_param_ptr->maximum_prepare_duration`: The maximum duration allowed for lane change
* preparation.
* - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle.
*
Expand Down Expand Up @@ -131,6 +131,24 @@ std::vector<double> calc_lon_acceleration_samples(
const CommonDataPtr & common_data_ptr, const double max_path_velocity,
const double prepare_duration);

/**
* @brief calculates the actual prepare duration that will be used for path generation
*
* @details computes the required prepare duration to be used for candidate path
* generation based on the elapsed time of turn signal activation, the minimum
* and maximum parameterized values for the prepare duration,
* and the minimum lane changing velocity.
*
* @param common_data_ptr Shared pointer to a CommonData structure, which includes
* lane change parameters and bpp common parameters.
* @param current_velocity current ego vehicle velocity.
* @param active_signal_duration elapsed time since turn signal activation.
* @return The calculated prepare duration value in seconds (s)
*/
double calc_actual_prepare_duration(
const CommonDataPtr & common_data_ptr, const double current_velocity,
const double active_signal_duration);

std::vector<PhaseMetrics> calc_prepare_phase_metrics(
const CommonDataPtr & common_data_ptr, const double current_velocity,
const double max_path_velocity, const double min_length_threshold = 0.0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,8 @@ struct TransientData
size_t current_path_seg_idx; // index of nearest segment to ego along current path
double current_path_velocity; // velocity of the current path at the ego position along the path

double lane_change_prepare_duration{0.0};

bool is_ego_near_current_terminal_start{false};
bool is_ego_stuck{false};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,8 @@ struct SafetyParameters

struct TrajectoryParameters
{
double prepare_duration{4.0};
double max_prepare_duration{4.0};
double min_prepare_duration{1.0};
double lateral_jerk{0.5};
double min_longitudinal_acc{-1.0};
double max_longitudinal_acc{1.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void LaneChangeInterface::updateData()
module_type_->setPreviousModuleOutput(getPreviousModuleOutput());
module_type_->update_lanes(getCurrentStatus() == ModuleStatus::RUNNING);
module_type_->update_filtered_objects();
module_type_->update_transient_data();
module_type_->update_transient_data(getCurrentStatus() == ModuleStatus::RUNNING);
module_type_->updateSpecialData();

if (isWaitingApproval() || module_type_->isAbortState()) {
Expand Down Expand Up @@ -155,10 +155,10 @@ BehaviorModuleOutput LaneChangeInterface::plan()

BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
{
*prev_approved_path_ = getPreviousModuleOutput().path;

BehaviorModuleOutput out = getPreviousModuleOutput();

*prev_approved_path_ = out.path;

module_type_->insert_stop_point(module_type_->get_current_lanes(), out.path);
out.turn_signal_info = module_type_->get_current_turn_signal_info();

Expand All @@ -168,7 +168,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color);
}

path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);
path_reference_ = std::make_shared<PathWithLaneId>(out.reference_path);
stop_pose_ = module_type_->getStopPose();

if (!module_type_->isValidPath()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,10 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s

// trajectory generation
{
p.trajectory.prepare_duration =
getOrDeclareParameter<double>(*node, parameter("trajectory.prepare_duration"));
p.trajectory.max_prepare_duration =
getOrDeclareParameter<double>(*node, parameter("trajectory.max_prepare_duration"));
p.trajectory.min_prepare_duration =
getOrDeclareParameter<double>(*node, parameter("trajectory.min_prepare_duration"));
p.trajectory.lateral_jerk =
getOrDeclareParameter<double>(*node, parameter("trajectory.lateral_jerk"));
p.trajectory.min_longitudinal_acc =
Expand All @@ -67,8 +69,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s
getOrDeclareParameter<int>(*node, parameter("trajectory.lat_acc_sampling_num"));

const auto max_acc = getOrDeclareParameter<double>(*node, "normal.max_acc");
p.trajectory.min_lane_changing_velocity =
std::min(p.trajectory.min_lane_changing_velocity, max_acc * p.trajectory.prepare_duration);
p.trajectory.min_lane_changing_velocity = std::min(
p.trajectory.min_lane_changing_velocity, max_acc * p.trajectory.max_prepare_duration);

// validation of trajectory parameters
if (p.trajectory.lon_acc_sampling_num < 1 || p.trajectory.lat_acc_sampling_num < 1) {
Expand Down Expand Up @@ -311,7 +313,10 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param

{
const std::string ns = "lane_change.trajectory.";
updateParam<double>(parameters, ns + "prepare_duration", p->trajectory.prepare_duration);
updateParam<double>(
parameters, ns + "max_prepare_duration", p->trajectory.max_prepare_duration);
updateParam<double>(
parameters, ns + "min_prepare_duration", p->trajectory.min_prepare_duration);
updateParam<double>(parameters, ns + "lateral_jerk", p->trajectory.lateral_jerk);
updateParam<double>(
parameters, ns + ".min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ void NormalLaneChange::update_lanes(const bool is_approved)
*common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_);
}

void NormalLaneChange::update_transient_data()
void NormalLaneChange::update_transient_data(const bool is_approved)
{
if (
!common_data_ptr_ || !common_data_ptr_->is_data_available() ||
Expand All @@ -150,6 +150,13 @@ void NormalLaneChange::update_transient_data()
prev_module_output_.path.points.at(nearest_seg_idx).point.longitudinal_velocity_mps;
transient_data.current_path_seg_idx = nearest_seg_idx;

const auto active_signal_duration =
signal_activation_time_ ? (clock_.now() - signal_activation_time_.value()).seconds() : 0.0;
transient_data.lane_change_prepare_duration =
is_approved ? status_.lane_change_path.info.duration.prepare
: calculation::calc_actual_prepare_duration(
common_data_ptr_, common_data_ptr_->get_ego_speed(), active_signal_duration);

std::tie(transient_data.lane_changing_length, transient_data.current_dist_buffer) =
calculation::calc_lc_length_and_dist_buffer(common_data_ptr_, get_current_lanes());

Expand Down Expand Up @@ -328,6 +335,8 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info() const
return get_terminal_turn_signal_info();
}

set_signal_activation_time();

return get_turn_signal(getEgoPose(), getLaneChangePath().info.lane_changing_end);
}

Expand Down Expand Up @@ -356,9 +365,14 @@ TurnSignalInfo NormalLaneChange::get_terminal_turn_signal_info() const
const auto nearest_yaw_threshold = common_param.ego_nearest_yaw_threshold;
const auto current_nearest_seg_idx = common_data_ptr_->transient_data.current_path_seg_idx;

return getTurnSignalDecider().overwrite_turn_signal(
const auto turn_signal_info = getTurnSignalDecider().overwrite_turn_signal(
path, current_pose, current_nearest_seg_idx, original_turn_signal_info,
terminal_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold);

set_signal_activation_time(
turn_signal_info.turn_signal.command != terminal_turn_signal_info.turn_signal.command);

return turn_signal_info;
}

LaneChangePath NormalLaneChange::getLaneChangePath() const
Expand Down Expand Up @@ -429,8 +443,6 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
output.path = utils::combinePath(output.path, *found_extended_path);
}
output.reference_path = getReferencePath();
output.turn_signal_info =
get_turn_signal(getEgoPose(), status_.lane_change_path.info.lane_changing_end);

if (isStopState()) {
const auto current_velocity = getEgoVelocity();
Expand All @@ -446,12 +458,17 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()

extendOutputDrivableArea(output);

const auto turn_signal_info =
get_turn_signal(getEgoPose(), status_.lane_change_path.info.lane_changing_end);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info,
output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);

set_signal_activation_time(
output.turn_signal_info.turn_signal.command != turn_signal_info.turn_signal.command);

return output;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ double calc_dist_to_last_fit_width(

double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr)
{
const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.prepare_duration;
const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.max_prepare_duration;
const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel;

return max_prepare_duration * ego_max_speed;
Expand Down Expand Up @@ -197,7 +197,7 @@ std::vector<double> calc_max_lane_change_lengths(

const auto & params = common_data_ptr->lc_param_ptr->trajectory;
const auto lat_jerk = params.lateral_jerk;
const auto t_prepare = params.prepare_duration;
const auto t_prepare = params.max_prepare_duration;
const auto current_velocity = common_data_ptr->get_ego_speed();
const auto path_velocity = common_data_ptr->transient_data.current_path_velocity;

Expand Down Expand Up @@ -400,18 +400,41 @@ double calc_lane_changing_acceleration(
prepare_longitudinal_acc);
}

double calc_actual_prepare_duration(
const CommonDataPtr & common_data_ptr, const double current_velocity,
const double active_signal_duration)
{
const auto & params = common_data_ptr->lc_param_ptr->trajectory;
const auto min_lc_velocity = params.min_lane_changing_velocity;

// need to ensure min prep duration is sufficient to reach minimum lane changing velocity
const auto min_prepare_duration = std::invoke([&]() -> double {
if (current_velocity >= min_lc_velocity) {
return params.min_prepare_duration;
}
const auto max_acc =
std::min(common_data_ptr->bpp_param_ptr->max_acc, params.max_longitudinal_acc);
if (max_acc < eps) {
return params.max_prepare_duration;
}
return (min_lc_velocity - current_velocity) / max_acc;
});

return std::max(params.max_prepare_duration - active_signal_duration, min_prepare_duration);
}

std::vector<double> calc_prepare_durations(const CommonDataPtr & common_data_ptr)
{
const auto & lc_param_ptr = common_data_ptr->lc_param_ptr;
const auto threshold = common_data_ptr->bpp_param_ptr->base_link2front +
lc_param_ptr->min_length_for_turn_signal_activation;
const auto max_prepare_duration = lc_param_ptr->trajectory.prepare_duration;

// TODO(Azu) this check seems to cause scenario failures.
if (common_data_ptr->transient_data.dist_to_terminal_start >= threshold) {
return {max_prepare_duration};
return {common_data_ptr->transient_data.lane_change_prepare_duration};
}

const auto max_prepare_duration = lc_param_ptr->trajectory.max_prepare_duration;
std::vector<double> prepare_durations;
constexpr double step = 0.5;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ TEST_F(TestNormalLaneChange, testGetPathWhenInvalid)
constexpr auto is_approved = true;
normal_lane_change_->update_lanes(!is_approved);
normal_lane_change_->update_filtered_objects();
normal_lane_change_->update_transient_data();
normal_lane_change_->update_transient_data(!is_approved);
normal_lane_change_->updateLaneChangeStatus();
const auto & lc_status = normal_lane_change_->getLaneChangeStatus();

Expand Down Expand Up @@ -261,7 +261,7 @@ TEST_F(TestNormalLaneChange, testGetPathWhenValid)
set_previous_approved_path();
normal_lane_change_->update_lanes(!is_approved);
normal_lane_change_->update_filtered_objects();
normal_lane_change_->update_transient_data();
normal_lane_change_->update_transient_data(!is_approved);
const auto lane_change_required = normal_lane_change_->isLaneChangeRequired();

ASSERT_TRUE(lane_change_required);
Expand Down

0 comments on commit 0992f1d

Please sign in to comment.