Skip to content

Commit

Permalink
build(autoware_behavior_path_avoidance_by_lane_change_module): revert…
Browse files Browse the repository at this point in the history
… clang-tidy fixes for naming functions

Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 18, 2024
1 parent 8e6580b commit 7398ba5
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -49,23 +49,23 @@ class AvoidanceByLaneChange : public NormalLaneChange
private:
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;

AvoidancePlanningData calc_avoidance_planning_data(AvoidanceDebugData & debug) const;
AvoidancePlanningData calcAvoidancePlanningData(AvoidanceDebugData & debug) const;
AvoidancePlanningData avoidance_data_;
mutable AvoidanceDebugData avoidance_debug_data_;

ObjectDataArray registered_objects_;
mutable ObjectDataArray stopped_objects_;
std::shared_ptr<AvoidanceHelper> avoidance_helper_;

std::optional<ObjectData> create_object_data(
std::optional<ObjectData> createObjectData(
const AvoidancePlanningData & data, const PredictedObject & object) const;

void fill_avoidance_target_objects(
AvoidancePlanningData & data, AvoidanceDebugData & debug) const;

double calc_min_avoidance_length(const ObjectData & nearest_object) const;
double calc_minimum_lane_change_length() const;
double calc_lateral_offset() const;
double calcMinAvoidanceLength(const ObjectData & nearest_object) const;
double calcMinimumLaneChangeLength() const;
double calcLateralOffset() const;
};
} // namespace autoware::behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,12 +79,12 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
}

const auto & nearest_object = data.target_objects.front();
const auto minimum_avoid_length = calc_min_avoidance_length(nearest_object);
const auto minimum_lane_change_length = calc_minimum_lane_change_length();
const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
const auto minimum_lane_change_length = calcMinimumLaneChangeLength();

lane_change_debug_.execution_area = createExecutionArea(
getCommonParam().vehicle_info, getEgoPose(),
std::max(minimum_lane_change_length, minimum_avoid_length), calc_lateral_offset());
std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());

RCLCPP_DEBUG(
logger_, "Conditions ? %f, %f, %f", nearest_object.longitudinal, minimum_lane_change_length,
Expand All @@ -102,7 +102,7 @@ void AvoidanceByLaneChange::updateSpecialData()
const auto p = std::dynamic_pointer_cast<AvoidanceParameters>(avoidance_parameters_);

avoidance_debug_data_ = DebugData();
avoidance_data_ = calc_avoidance_planning_data(avoidance_debug_data_);
avoidance_data_ = calcAvoidancePlanningData(avoidance_debug_data_);

if (avoidance_data_.target_objects.empty()) {
direction_ = Direction::NONE;
Expand All @@ -123,7 +123,7 @@ void AvoidanceByLaneChange::updateSpecialData()
[](auto a, auto b) { return a.longitudinal < b.longitudinal; });
}

AvoidancePlanningData AvoidanceByLaneChange::calc_avoidance_planning_data(
AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
AvoidanceDebugData & debug) const
{
AvoidancePlanningData data;
Expand Down Expand Up @@ -179,7 +179,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
ObjectDataArray target_lane_objects;
target_lane_objects.reserve(object_within_target_lane.objects.size());
for (const auto & obj : object_within_target_lane.objects) {
const auto target_lane_object = create_object_data(data, obj);
const auto target_lane_object = createObjectData(data, obj);
if (!target_lane_object) {
continue;
}
Expand All @@ -190,7 +190,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
data.target_objects = target_lane_objects;
}

std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(
const AvoidancePlanningData & data, const PredictedObject & object) const
{
using boost::geometry::return_centroid;
Expand Down Expand Up @@ -255,7 +255,7 @@ std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
return object_data;
}

double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & nearest_object) const
double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_object) const
{
const auto ego_width = getCommonParam().vehicle_width;
const auto nearest_object_type =
Expand All @@ -276,7 +276,7 @@ double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & neare
return avoidance_helper_->getMinAvoidanceDistance(shift_length);
}

double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
{
const auto current_lanes = getCurrentLanes();
if (current_lanes.empty()) {
Expand All @@ -292,7 +292,7 @@ double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
lane_change_parameters_->backward_length_buffer_for_end_of_lane);
}

double AvoidanceByLaneChange::calc_lateral_offset() const
double AvoidanceByLaneChange::calcLateralOffset() const
{
auto additional_lat_offset{0.0};
for (const auto & [type, p] : avoidance_parameters_->object_parameters) {
Expand Down

0 comments on commit 7398ba5

Please sign in to comment.