Skip to content

Commit 7398ba5

Browse files
committed
build(autoware_behavior_path_avoidance_by_lane_change_module): revert clang-tidy fixes for naming functions
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 8e6580b commit 7398ba5

File tree

2 files changed

+15
-15
lines changed
  • planning/behavior_path_avoidance_by_lane_change_module

2 files changed

+15
-15
lines changed

planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -49,23 +49,23 @@ class AvoidanceByLaneChange : public NormalLaneChange
4949
private:
5050
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;
5151

52-
AvoidancePlanningData calc_avoidance_planning_data(AvoidanceDebugData & debug) const;
52+
AvoidancePlanningData calcAvoidancePlanningData(AvoidanceDebugData & debug) const;
5353
AvoidancePlanningData avoidance_data_;
5454
mutable AvoidanceDebugData avoidance_debug_data_;
5555

5656
ObjectDataArray registered_objects_;
5757
mutable ObjectDataArray stopped_objects_;
5858
std::shared_ptr<AvoidanceHelper> avoidance_helper_;
5959

60-
std::optional<ObjectData> create_object_data(
60+
std::optional<ObjectData> createObjectData(
6161
const AvoidancePlanningData & data, const PredictedObject & object) const;
6262

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

66-
double calc_min_avoidance_length(const ObjectData & nearest_object) const;
67-
double calc_minimum_lane_change_length() const;
68-
double calc_lateral_offset() const;
66+
double calcMinAvoidanceLength(const ObjectData & nearest_object) const;
67+
double calcMinimumLaneChangeLength() const;
68+
double calcLateralOffset() const;
6969
};
7070
} // namespace autoware::behavior_path_planner
7171

planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -79,12 +79,12 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
7979
}
8080

8181
const auto & nearest_object = data.target_objects.front();
82-
const auto minimum_avoid_length = calc_min_avoidance_length(nearest_object);
83-
const auto minimum_lane_change_length = calc_minimum_lane_change_length();
82+
const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
83+
const auto minimum_lane_change_length = calcMinimumLaneChangeLength();
8484

8585
lane_change_debug_.execution_area = createExecutionArea(
8686
getCommonParam().vehicle_info, getEgoPose(),
87-
std::max(minimum_lane_change_length, minimum_avoid_length), calc_lateral_offset());
87+
std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());
8888

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

104104
avoidance_debug_data_ = DebugData();
105-
avoidance_data_ = calc_avoidance_planning_data(avoidance_debug_data_);
105+
avoidance_data_ = calcAvoidancePlanningData(avoidance_debug_data_);
106106

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

126-
AvoidancePlanningData AvoidanceByLaneChange::calc_avoidance_planning_data(
126+
AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
127127
AvoidanceDebugData & debug) const
128128
{
129129
AvoidancePlanningData data;
@@ -179,7 +179,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
179179
ObjectDataArray target_lane_objects;
180180
target_lane_objects.reserve(object_within_target_lane.objects.size());
181181
for (const auto & obj : object_within_target_lane.objects) {
182-
const auto target_lane_object = create_object_data(data, obj);
182+
const auto target_lane_object = createObjectData(data, obj);
183183
if (!target_lane_object) {
184184
continue;
185185
}
@@ -190,7 +190,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
190190
data.target_objects = target_lane_objects;
191191
}
192192

193-
std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
193+
std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(
194194
const AvoidancePlanningData & data, const PredictedObject & object) const
195195
{
196196
using boost::geometry::return_centroid;
@@ -255,7 +255,7 @@ std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
255255
return object_data;
256256
}
257257

258-
double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & nearest_object) const
258+
double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_object) const
259259
{
260260
const auto ego_width = getCommonParam().vehicle_width;
261261
const auto nearest_object_type =
@@ -276,7 +276,7 @@ double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & neare
276276
return avoidance_helper_->getMinAvoidanceDistance(shift_length);
277277
}
278278

279-
double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
279+
double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
280280
{
281281
const auto current_lanes = getCurrentLanes();
282282
if (current_lanes.empty()) {
@@ -292,7 +292,7 @@ double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
292292
lane_change_parameters_->backward_length_buffer_for_end_of_lane);
293293
}
294294

295-
double AvoidanceByLaneChange::calc_lateral_offset() const
295+
double AvoidanceByLaneChange::calcLateralOffset() const
296296
{
297297
auto additional_lat_offset{0.0};
298298
for (const auto & [type, p] : avoidance_parameters_->object_parameters) {

0 commit comments

Comments
 (0)