Skip to content

Commit

Permalink
refactor(lane_change): rename lane_change_utils namespace (#3332)
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 authored and purewater0901 committed Apr 11, 2023
1 parent 49fb3f9 commit 8faddc6
Show file tree
Hide file tree
Showing 6 changed files with 56 additions and 56 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include <utility>
#include <vector>

namespace behavior_path_planner::lane_change_utils
namespace behavior_path_planner::util::lane_change
{
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
Expand Down Expand Up @@ -181,5 +181,5 @@ lanelet::ConstLanelets getLaneChangeLanes(
const std::shared_ptr<const PlannerData> & planner_data,
const lanelet::ConstLanelets & current_lanes, const double lane_change_lane_length,
const double prepare_duration, const Direction direction, const LaneChangeModuleType type);
} // namespace behavior_path_planner::lane_change_utils
} // namespace behavior_path_planner::util::lane_change
#endif // BEHAVIOR_PATH_PLANNER__UTIL__LANE_CHANGE__UTIL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -639,7 +639,7 @@ ModuleStatus AvoidanceByLCModule::updateState()
}
}

const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane(
const auto is_within_current_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), planner_data_->parameters);
if (isAbortState() && !is_within_current_lane) {
current_state_ = ModuleStatus::RUNNING;
Expand Down Expand Up @@ -715,7 +715,7 @@ void AvoidanceByLCModule::resetPathIfAbort()
{
if (!is_abort_approval_requested_) {
#ifdef USE_OLD_ARCHITECTURE
const auto lateral_shift = lane_change_utils::getLateralShift(*abort_path_);
const auto lateral_shift = util::lane_change::getLateralShift(*abort_path_);
if (lateral_shift > 0.0) {
removePreviousRTCStatusRight();
uuid_map_.at("right") = generateUUID();
Expand Down Expand Up @@ -779,7 +779,7 @@ CandidateOutput AvoidanceByLCModule::planCandidate() const
}

output.path_candidate = selected_path.path;
output.lateral_shift = lane_change_utils::getLateralShift(selected_path);
output.lateral_shift = util::lane_change::getLateralShift(selected_path);
output.start_distance_to_path_change = motion_utils::calcSignedArcLength(
selected_path.path.points, getEgoPose().position, selected_path.shift_line.start.position);
output.finish_distance_to_path_change = motion_utils::calcSignedArcLength(
Expand All @@ -792,7 +792,7 @@ CandidateOutput AvoidanceByLCModule::planCandidate() const
BehaviorModuleOutput AvoidanceByLCModule::planWaitingApproval()
{
#ifdef USE_OLD_ARCHITECTURE
const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane(
const auto is_within_current_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), planner_data_->parameters);
if (is_within_current_lane) {
prev_approved_path_ = getReferencePath();
Expand Down Expand Up @@ -989,14 +989,14 @@ std::pair<bool, bool> AvoidanceByLCModule::getSafePath(
// find candidate paths
LaneChangePaths valid_paths;
#ifdef USE_OLD_ARCHITECTURE
const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths(
const auto [found_valid_path, found_safe_path] = util::lane_change::getLaneChangePaths(
*route_handler, current_lanes, lane_change_lanes, current_pose, current_twist,
planner_data_->dynamic_object, common_parameters, *parameters_->lane_change, check_distance,
&valid_paths, &object_debug_);
#else
const auto o_front = avoidance_data_.target_objects.front();
const auto direction = isOnRight(o_front) ? Direction::LEFT : Direction::RIGHT;
const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths(
const auto [found_valid_path, found_safe_path] = util::lane_change::getLaneChangePaths(
*getPreviousModuleOutput().path, *route_handler, current_lanes, lane_change_lanes, current_pose,
current_twist, planner_data_->dynamic_object, common_parameters, *parameters_->lane_change,
check_distance, direction, &valid_paths, &object_debug_);
Expand Down Expand Up @@ -1038,7 +1038,7 @@ bool AvoidanceByLCModule::isValidPath(const PathWithLaneId & path) const
const auto & route_handler = planner_data_->route_handler;

// check lane departure
const auto drivable_lanes = lane_change_utils::generateDrivableLanes(
const auto drivable_lanes = util::lane_change::generateDrivableLanes(
*route_handler, util::extendLanes(route_handler, status_.current_lanes),
util::extendLanes(route_handler, status_.lane_change_lanes));
const auto expanded_lanes = util::expandLanelets(
Expand Down Expand Up @@ -1103,7 +1103,7 @@ bool AvoidanceByLCModule::isAbortConditionSatisfied()

if (!is_path_safe) {
const auto & common_parameters = planner_data_->parameters;
const bool is_within_original_lane = lane_change_utils::isEgoWithinOriginalLane(
const bool is_within_original_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), common_parameters);

if (is_within_original_lane) {
Expand All @@ -1121,7 +1121,7 @@ bool AvoidanceByLCModule::isAbortConditionSatisfied()
return false;
}

const auto found_abort_path = lane_change_utils::getAbortPaths(
const auto found_abort_path = util::lane_change::getAbortPaths(
planner_data_, status_.lane_change_path, ego_pose_before_collision, common_parameters,
*parameters_->lane_change);

Expand Down Expand Up @@ -1283,7 +1283,7 @@ void AvoidanceByLCModule::generateExtendedDrivableArea(PathWithLaneId & path)
{
const auto & common_parameters = planner_data_->parameters;
const auto & route_handler = planner_data_->route_handler;
const auto drivable_lanes = lane_change_utils::generateDrivableLanes(
const auto drivable_lanes = util::lane_change::generateDrivableLanes(
*route_handler, status_.current_lanes, status_.lane_change_lanes);
const auto shorten_lanes = util::cutOverlappedLanes(path, drivable_lanes);
const auto expanded_lanes = util::expandLanelets(
Expand All @@ -1303,17 +1303,17 @@ bool AvoidanceByLCModule::isApprovedPathSafe(Pose & ego_pose_before_collision) c
const auto & path = status_.lane_change_path;

// get lanes used for detection
const auto check_lanes = lane_change_utils::getExtendedTargetLanesForCollisionCheck(
const auto check_lanes = util::lane_change::getExtendedTargetLanesForCollisionCheck(
*route_handler, path.target_lanelets.front(), current_pose, check_distance_);

std::unordered_map<std::string, CollisionCheckDebug> debug_data;
const auto lateral_buffer =
lane_change_utils::calcLateralBufferForFiltering(common_parameters.vehicle_width);
const auto dynamic_object_indices = lane_change_utils::filterObjectIndices(
util::lane_change::calcLateralBufferForFiltering(common_parameters.vehicle_width);
const auto dynamic_object_indices = util::lane_change::filterObjectIndices(
{path}, *dynamic_objects, check_lanes, current_pose, common_parameters.forward_path_length,
*lane_change_parameters, lateral_buffer);

return lane_change_utils::isLaneChangePathSafe(
return util::lane_change::isLaneChangePathSafe(
path, dynamic_objects, dynamic_object_indices, current_pose, current_twist, common_parameters,
*parameters_->lane_change, common_parameters.expected_front_deceleration_for_abort,
common_parameters.expected_rear_deceleration_for_abort, ego_pose_before_collision, debug_data,
Expand All @@ -1328,7 +1328,7 @@ void AvoidanceByLCModule::updateOutputTurnSignal(BehaviorModuleOutput & output)
planner_data_->parameters);
output.turn_signal_info.turn_signal.command = turn_signal_info.first.command;

lane_change_utils::get_turn_signal_info(status_.lane_change_path, &output.turn_signal_info);
util::lane_change::get_turn_signal_info(status_.lane_change_path, &output.turn_signal_info);
}

bool AvoidanceByLCModule::isTargetObjectType(const PredictedObject & object) const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ BT::NodeStatus ExternalRequestLaneChangeModule::updateState()
return current_state_;
}

const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane(
const auto is_within_current_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), planner_data_->parameters);
if (isAbortState() && !is_within_current_lane) {
current_state_ = BT::NodeStatus::RUNNING;
Expand Down Expand Up @@ -209,7 +209,7 @@ CandidateOutput ExternalRequestLaneChangeModule::planCandidate() const
}

output.path_candidate = selected_path.path;
output.lateral_shift = lane_change_utils::getLateralShift(selected_path);
output.lateral_shift = util::lane_change::getLateralShift(selected_path);
output.start_distance_to_path_change = motion_utils::calcSignedArcLength(
selected_path.path.points, getEgoPose().position, selected_path.shift_line.start.position);
output.finish_distance_to_path_change = motion_utils::calcSignedArcLength(
Expand All @@ -221,7 +221,7 @@ CandidateOutput ExternalRequestLaneChangeModule::planCandidate() const

BehaviorModuleOutput ExternalRequestLaneChangeModule::planWaitingApproval()
{
const auto is_within_current_lane = lane_change_utils::isEgoWithinOriginalLane(
const auto is_within_current_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), planner_data_->parameters);

if (is_within_current_lane) {
Expand Down Expand Up @@ -365,7 +365,7 @@ std::pair<bool, bool> ExternalRequestLaneChangeModule::getSafePath(

// find candidate paths
LaneChangePaths valid_paths;
const auto [found_valid_path, found_safe_path] = lane_change_utils::getLaneChangePaths(
const auto [found_valid_path, found_safe_path] = util::lane_change::getLaneChangePaths(
*route_handler, current_lanes, lane_change_lanes, current_pose, current_twist,
planner_data_->dynamic_object, common_parameters, *parameters_, check_distance, &valid_paths,
&object_debug_);
Expand Down Expand Up @@ -401,7 +401,7 @@ bool ExternalRequestLaneChangeModule::isValidPath(const PathWithLaneId & path) c
const auto & route_handler = planner_data_->route_handler;

// check lane departure
const auto drivable_lanes = lane_change_utils::generateDrivableLanes(
const auto drivable_lanes = util::lane_change::generateDrivableLanes(
*route_handler, util::extendLanes(route_handler, status_.current_lanes),
util::extendLanes(route_handler, status_.lane_change_lanes));
const auto expanded_lanes = util::expandLanelets(
Expand Down Expand Up @@ -468,7 +468,7 @@ bool ExternalRequestLaneChangeModule::isAbortConditionSatisfied()

if (!is_path_safe) {
const auto & common_parameters = planner_data_->parameters;
const bool is_within_original_lane = lane_change_utils::isEgoWithinOriginalLane(
const bool is_within_original_lane = util::lane_change::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), common_parameters);

if (is_within_original_lane) {
Expand All @@ -486,7 +486,7 @@ bool ExternalRequestLaneChangeModule::isAbortConditionSatisfied()
return false;
}

const auto found_abort_path = lane_change_utils::getAbortPaths(
const auto found_abort_path = util::lane_change::getAbortPaths(
planner_data_, status_.lane_change_path, ego_pose_before_collision, common_parameters,
*parameters_);

Expand Down Expand Up @@ -635,7 +635,7 @@ void ExternalRequestLaneChangeModule::generateExtendedDrivableArea(PathWithLaneI
{
const auto & common_parameters = planner_data_->parameters;
const auto & route_handler = planner_data_->route_handler;
const auto drivable_lanes = lane_change_utils::generateDrivableLanes(
const auto drivable_lanes = util::lane_change::generateDrivableLanes(
*route_handler, status_.current_lanes, status_.lane_change_lanes);
const auto expanded_lanes = util::expandLanelets(
drivable_lanes, parameters_->drivable_area_left_bound_offset,
Expand All @@ -656,18 +656,18 @@ bool ExternalRequestLaneChangeModule::isApprovedPathSafe(Pose & ego_pose_before_

constexpr double check_distance = 100.0;
// get lanes used for detection
const auto check_lanes = lane_change_utils::getExtendedTargetLanesForCollisionCheck(
const auto check_lanes = util::lane_change::getExtendedTargetLanesForCollisionCheck(
*route_handler, path.target_lanelets.front(), current_pose, check_distance);

std::unordered_map<std::string, CollisionCheckDebug> debug_data;

const auto lateral_buffer =
lane_change_utils::calcLateralBufferForFiltering(common_parameters.vehicle_width);
const auto dynamic_object_indices = lane_change_utils::filterObjectIndices(
util::lane_change::calcLateralBufferForFiltering(common_parameters.vehicle_width);
const auto dynamic_object_indices = util::lane_change::filterObjectIndices(
{path}, *dynamic_objects, check_lanes, current_pose, common_parameters.forward_path_length,
lane_change_parameters, lateral_buffer);

return lane_change_utils::isLaneChangePathSafe(
return util::lane_change::isLaneChangePathSafe(
path, dynamic_objects, dynamic_object_indices, current_pose, current_twist, common_parameters,
*parameters_, common_parameters.expected_front_deceleration_for_abort,
common_parameters.expected_rear_deceleration_for_abort, ego_pose_before_collision, debug_data,
Expand All @@ -683,7 +683,7 @@ void ExternalRequestLaneChangeModule::updateOutputTurnSignal(BehaviorModuleOutpu
planner_data_->parameters);
output.turn_signal_info.turn_signal.command = turn_signal_info.first.command;

lane_change_utils::get_turn_signal_info(status_.lane_change_path, &output.turn_signal_info);
util::lane_change::get_turn_signal_info(status_.lane_change_path, &output.turn_signal_info);
}

void ExternalRequestLaneChangeModule::calcTurnSignalInfo()
Expand Down
Loading

0 comments on commit 8faddc6

Please sign in to comment.