Skip to content

Commit

Permalink
RT1-8004 Rename isVehicleStuck to is_ego_stuck()
Browse files Browse the repository at this point in the history
Signed-off-by: Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Oct 4, 2024
1 parent 67114cc commit a6d0e98
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ if (max_lane_change_length > ego's distance to the end of the current lanes.) t
stop
endif
if (isVehicleStuck(current_lanes)) then (yes)
if ego is stuck in the current lanes then (yes)
:Return **sampled acceleration values**;
stop
else (no)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ class NormalLaneChange : public LaneChangeBase

double get_max_velocity_for_safety_check() const;

bool isVehicleStuck() const;
bool is_ego_stuck() const;

/**
* @brief Checks if the given pose is a valid starting point for a lane change.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ void NormalLaneChange::update_transient_data()
transient_data.dist_to_terminal_start < transient_data.max_prepare_length;

updateStopTime();
transient_data.is_ego_stuck = isVehicleStuck();
transient_data.is_ego_stuck = is_ego_stuck();

RCLCPP_DEBUG(
logger_, "acc - min: %.4f, max: %.4f", transient_data.acc.min, transient_data.acc.max);
Expand Down Expand Up @@ -2139,7 +2139,7 @@ double NormalLaneChange::get_max_velocity_for_safety_check() const
return getCommonParam().max_vel;
}

bool NormalLaneChange::isVehicleStuck() const
bool NormalLaneChange::is_ego_stuck() const
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
const auto & lc_param_ptr = common_data_ptr_->lc_param_ptr;
Expand Down

0 comments on commit a6d0e98

Please sign in to comment.