Skip to content

Commit 27264d2

Browse files
committed
fix(autoware_behavior_path_avoidance_by_lane_change_module): fix clang-tidy issues
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 4fac342 commit 27264d2

File tree

7 files changed

+39
-51
lines changed

7 files changed

+39
-51
lines changed

planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp

+4-7
Original file line numberDiff line numberDiff line change
@@ -16,13 +16,11 @@
1616

1717
#include "behavior_path_avoidance_module/data_structs.hpp"
1818

19-
namespace autoware
19+
namespace autoware::behavior_path_planner
2020
{
21-
namespace behavior_path_planner
22-
{
23-
using ::behavior_path_planner::DebugData;
21+
using ::behavior_path_planner::AvoidanceParameters;
2422

25-
struct AvoidanceByLCParameters : public ::behavior_path_planner::AvoidanceParameters
23+
struct AvoidanceByLCParameters : public AvoidanceParameters
2624
{
2725
// execute only when the target object longitudinal distance is larger than this param.
2826
double execute_object_longitudinal_margin{0.0};
@@ -34,7 +32,6 @@ struct AvoidanceByLCParameters : public ::behavior_path_planner::AvoidanceParame
3432
{
3533
}
3634
};
37-
} // namespace behavior_path_planner
38-
} // namespace autoware
35+
} // namespace autoware::behavior_path_planner
3936

4037
#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_

planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp

+2-6
Original file line numberDiff line numberDiff line change
@@ -25,11 +25,8 @@
2525
#include <string>
2626
#include <unordered_map>
2727

28-
namespace autoware
28+
namespace autoware::behavior_path_planner
2929
{
30-
namespace behavior_path_planner
31-
{
32-
using ::behavior_path_planner::Direction;
3330
using ::behavior_path_planner::LaneChangeInterface;
3431
using ::behavior_path_planner::ObjectsOfInterestMarkerInterface;
3532
using ::behavior_path_planner::RTCInterface;
@@ -52,7 +49,6 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface
5249
protected:
5350
void updateRTCStatus(const double start_distance, const double finish_distance) override;
5451
};
55-
} // namespace behavior_path_planner
56-
} // namespace autoware
52+
} // namespace autoware::behavior_path_planner
5753

5854
#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_

planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp

+2-9
Original file line numberDiff line numberDiff line change
@@ -26,17 +26,11 @@
2626
#include <unordered_map>
2727
#include <vector>
2828

29-
namespace autoware
29+
namespace autoware::behavior_path_planner
3030
{
31-
namespace behavior_path_planner
32-
{
33-
using ::behavior_path_planner::AvoidancePlanningData;
3431
using ::behavior_path_planner::LaneChangeModuleManager;
3532
using ::behavior_path_planner::LaneChangeModuleType;
36-
using ::behavior_path_planner::ObjectParameter;
3733
using ::behavior_path_planner::SceneModuleInterface;
38-
using ::behavior_path_planner::SceneModuleManagerInterface;
39-
using ::route_handler::Direction;
4034

4135
class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
4236
{
@@ -55,7 +49,6 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
5549
private:
5650
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;
5751
};
58-
} // namespace behavior_path_planner
59-
} // namespace autoware
52+
} // namespace autoware::behavior_path_planner
6053

6154
#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_

planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp

+12-17
Original file line numberDiff line numberDiff line change
@@ -21,28 +21,24 @@
2121

2222
#include <memory>
2323

24-
namespace autoware
24+
namespace autoware::behavior_path_planner
2525
{
26-
namespace behavior_path_planner
27-
{
28-
using ::behavior_path_planner::AvoidanceParameters;
29-
using ::route_handler::Direction;
26+
using ::behavior_path_planner::DebugData;
3027
using AvoidanceDebugData = DebugData;
3128
using ::behavior_path_planner::AvoidancePlanningData;
32-
using ::behavior_path_planner::LaneChangeModuleType;
3329
using ::behavior_path_planner::LaneChangeParameters;
3430
using ::behavior_path_planner::ObjectData;
3531
using ::behavior_path_planner::ObjectDataArray;
36-
using ::behavior_path_planner::Point2d;
3732
using ::behavior_path_planner::PredictedObject;
3833
using ::behavior_path_planner::helper::avoidance::AvoidanceHelper;
34+
using ::behavior_path_planner::NormalLaneChange;
3935

40-
class AvoidanceByLaneChange : public ::behavior_path_planner::NormalLaneChange
36+
class AvoidanceByLaneChange : public NormalLaneChange
4137
{
4238
public:
4339
AvoidanceByLaneChange(
4440
const std::shared_ptr<LaneChangeParameters> & parameters,
45-
std::shared_ptr<AvoidanceByLCParameters> avoidance_by_lane_change_parameters);
41+
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters);
4642

4743
bool specialRequiredCheck() const override;
4844

@@ -53,24 +49,23 @@ class AvoidanceByLaneChange : public ::behavior_path_planner::NormalLaneChange
5349
private:
5450
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;
5551

56-
AvoidancePlanningData calcAvoidancePlanningData(AvoidanceDebugData & debug) const;
52+
AvoidancePlanningData calc_avoidance_planning_data(AvoidanceDebugData & debug) const;
5753
AvoidancePlanningData avoidance_data_;
5854
mutable AvoidanceDebugData avoidance_debug_data_;
5955

6056
ObjectDataArray registered_objects_;
6157
mutable ObjectDataArray stopped_objects_;
6258
std::shared_ptr<AvoidanceHelper> avoidance_helper_;
6359

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

67-
void fillAvoidanceTargetObjects(AvoidancePlanningData & data, AvoidanceDebugData & debug) const;
63+
void fill_avoidance_target_objects(AvoidancePlanningData & data, AvoidanceDebugData & debug) const;
6864

69-
double calcMinAvoidanceLength(const ObjectData & nearest_object) const;
70-
double calcMinimumLaneChangeLength() const;
71-
double calcLateralOffset() const;
65+
double calc_min_avoidance_length(const ObjectData & nearest_object) const;
66+
double calc_minimum_lane_change_length() const;
67+
double calc_lateral_offset() const;
7268
};
73-
} // namespace behavior_path_planner
74-
} // namespace autoware
69+
} // namespace autoware::behavior_path_planner
7570

7671
#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_

planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222

2323
namespace autoware::behavior_path_planner
2424
{
25+
using ::route_handler::Direction;
26+
2527
AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface(
2628
const std::string & name, rclcpp::Node & node,
2729
const std::shared_ptr<LaneChangeParameters> & parameters,

planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727

2828
namespace autoware::behavior_path_planner
2929
{
30+
using ::behavior_path_planner::ObjectParameter;
31+
3032
void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
3133
{
3234
using autoware_auto_perception_msgs::msg::ObjectClassification;

planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp

+15-12
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,9 @@
3535
namespace autoware::behavior_path_planner
3636
{
3737
using ::behavior_path_planner::utils::lane_change::debug::createExecutionArea;
38+
using ::route_handler::Direction;
39+
using ::behavior_path_planner::LaneChangeModuleType;
40+
using ::behavior_path_planner::Point2d;
3841

3942
AvoidanceByLaneChange::AvoidanceByLaneChange(
4043
const std::shared_ptr<LaneChangeParameters> & parameters,
@@ -76,12 +79,12 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
7679
}
7780

7881
const auto & nearest_object = data.target_objects.front();
79-
const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
80-
const auto minimum_lane_change_length = calcMinimumLaneChangeLength();
82+
const auto minimum_avoid_length = calc_min_avoidance_length(nearest_object);
83+
const auto minimum_lane_change_length = calc_minimum_lane_change_length();
8184

8285
lane_change_debug_.execution_area = createExecutionArea(
8386
getCommonParam().vehicle_info, getEgoPose(),
84-
std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());
87+
std::max(minimum_lane_change_length, minimum_avoid_length), calc_lateral_offset());
8588

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

101104
avoidance_debug_data_ = DebugData();
102-
avoidance_data_ = calcAvoidancePlanningData(avoidance_debug_data_);
105+
avoidance_data_ = calc_avoidance_planning_data(avoidance_debug_data_);
103106

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

123-
AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
126+
AvoidancePlanningData AvoidanceByLaneChange::calc_avoidance_planning_data(
124127
AvoidanceDebugData & debug) const
125128
{
126129
AvoidancePlanningData data;
@@ -136,12 +139,12 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
136139

137140
data.current_lanelets = getCurrentLanes();
138141

139-
fillAvoidanceTargetObjects(data, debug);
142+
fill_avoidance_target_objects(data, debug);
140143

141144
return data;
142145
}
143146

144-
void AvoidanceByLaneChange::fillAvoidanceTargetObjects(
147+
void AvoidanceByLaneChange::fill_avoidance_target_objects(
145148
AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const
146149
{
147150
const auto p = std::dynamic_pointer_cast<AvoidanceParameters>(avoidance_parameters_);
@@ -176,7 +179,7 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects(
176179
ObjectDataArray target_lane_objects;
177180
target_lane_objects.reserve(object_within_target_lane.objects.size());
178181
for (const auto & obj : object_within_target_lane.objects) {
179-
const auto target_lane_object = createObjectData(data, obj);
182+
const auto target_lane_object = create_object_data(data, obj);
180183
if (!target_lane_object) {
181184
continue;
182185
}
@@ -187,7 +190,7 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects(
187190
data.target_objects = target_lane_objects;
188191
}
189192

190-
std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(
193+
std::optional<ObjectData> AvoidanceByLaneChange::create_object_data(
191194
const AvoidancePlanningData & data, const PredictedObject & object) const
192195
{
193196
using boost::geometry::return_centroid;
@@ -252,7 +255,7 @@ std::optional<ObjectData> AvoidanceByLaneChange::createObjectData(
252255
return object_data;
253256
}
254257

255-
double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_object) const
258+
double AvoidanceByLaneChange::calc_min_avoidance_length(const ObjectData & nearest_object) const
256259
{
257260
const auto ego_width = getCommonParam().vehicle_width;
258261
const auto nearest_object_type =
@@ -273,7 +276,7 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_
273276
return avoidance_helper_->getMinAvoidanceDistance(shift_length);
274277
}
275278

276-
double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
279+
double AvoidanceByLaneChange::calc_minimum_lane_change_length() const
277280
{
278281
const auto current_lanes = getCurrentLanes();
279282
if (current_lanes.empty()) {
@@ -289,7 +292,7 @@ double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
289292
lane_change_parameters_->backward_length_buffer_for_end_of_lane);
290293
}
291294

292-
double AvoidanceByLaneChange::calcLateralOffset() const
295+
double AvoidanceByLaneChange::calc_lateral_offset() const
293296
{
294297
auto additional_lat_offset{0.0};
295298
for (const auto & [type, p] : avoidance_parameters_->object_parameters) {

0 commit comments

Comments
 (0)