@@ -79,12 +79,12 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
79
79
}
80
80
81
81
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 ();
84
84
85
85
lane_change_debug_.execution_area = createExecutionArea (
86
86
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 ());
88
88
89
89
RCLCPP_DEBUG (
90
90
logger_, " Conditions ? %f, %f, %f" , nearest_object.longitudinal , minimum_lane_change_length,
@@ -102,7 +102,7 @@ void AvoidanceByLaneChange::updateSpecialData()
102
102
const auto p = std::dynamic_pointer_cast<AvoidanceParameters>(avoidance_parameters_);
103
103
104
104
avoidance_debug_data_ = DebugData ();
105
- avoidance_data_ = calc_avoidance_planning_data (avoidance_debug_data_);
105
+ avoidance_data_ = calcAvoidancePlanningData (avoidance_debug_data_);
106
106
107
107
if (avoidance_data_.target_objects .empty ()) {
108
108
direction_ = Direction::NONE;
@@ -123,7 +123,7 @@ void AvoidanceByLaneChange::updateSpecialData()
123
123
[](auto a, auto b) { return a.longitudinal < b.longitudinal ; });
124
124
}
125
125
126
- AvoidancePlanningData AvoidanceByLaneChange::calc_avoidance_planning_data (
126
+ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData (
127
127
AvoidanceDebugData & debug) const
128
128
{
129
129
AvoidancePlanningData data;
@@ -179,7 +179,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
179
179
ObjectDataArray target_lane_objects;
180
180
target_lane_objects.reserve (object_within_target_lane.objects .size ());
181
181
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);
183
183
if (!target_lane_object) {
184
184
continue ;
185
185
}
@@ -190,7 +190,7 @@ void AvoidanceByLaneChange::fill_avoidance_target_objects(
190
190
data.target_objects = target_lane_objects;
191
191
}
192
192
193
- std::optional<ObjectData> AvoidanceByLaneChange::create_object_data (
193
+ std::optional<ObjectData> AvoidanceByLaneChange::createObjectData (
194
194
const AvoidancePlanningData & data, const PredictedObject & object) const
195
195
{
196
196
using boost::geometry::return_centroid;
@@ -255,7 +255,7 @@ std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
255
255
return object_data;
256
256
}
257
257
258
- double AvoidanceByLaneChange::calc_min_avoidance_length (const ObjectData & nearest_object) const
258
+ double AvoidanceByLaneChange::calcMinAvoidanceLength (const ObjectData & nearest_object) const
259
259
{
260
260
const auto ego_width = getCommonParam ().vehicle_width ;
261
261
const auto nearest_object_type =
@@ -276,7 +276,7 @@ double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & neare
276
276
return avoidance_helper_->getMinAvoidanceDistance (shift_length);
277
277
}
278
278
279
- double AvoidanceByLaneChange::calc_minimum_lane_change_length () const
279
+ double AvoidanceByLaneChange::calcMinimumLaneChangeLength () const
280
280
{
281
281
const auto current_lanes = getCurrentLanes ();
282
282
if (current_lanes.empty ()) {
@@ -292,7 +292,7 @@ double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
292
292
lane_change_parameters_->backward_length_buffer_for_end_of_lane );
293
293
}
294
294
295
- double AvoidanceByLaneChange::calc_lateral_offset () const
295
+ double AvoidanceByLaneChange::calcLateralOffset () const
296
296
{
297
297
auto additional_lat_offset{0.0 };
298
298
for (const auto & [type, p] : avoidance_parameters_->object_parameters ) {
0 commit comments