Skip to content

Commit cdb3d4a

Browse files
authored
refactor(behavior_path_planner_common): fix namespace of drivable_area_expansion (#7444)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 1fcd5c6 commit cdb3d4a

File tree

19 files changed

+48
-44
lines changed

19 files changed

+48
-44
lines changed

Diff for: planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4444
const auto planning_test_utils_dir =
4545
ament_index_cpp::get_package_share_directory("planning_test_utils");
4646
const auto behavior_path_planner_dir =
47-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
47+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
4848

4949
std::vector<std::string> module_names;
5050
module_names.emplace_back("autoware::behavior_path_planner::DynamicAvoidanceModuleManager");

Diff for: planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4646
const auto planning_test_utils_dir =
4747
ament_index_cpp::get_package_share_directory("planning_test_utils");
4848
const auto behavior_path_planner_dir =
49-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
49+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
5050
const auto behavior_path_lane_change_module_dir =
5151
ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module");
5252

Diff for: planning/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4646
const auto planning_test_utils_dir =
4747
ament_index_cpp::get_package_share_directory("planning_test_utils");
4848
const auto behavior_path_planner_dir =
49-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
49+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
5050
const auto behavior_path_lane_change_module_dir =
5151
ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module");
5252

Diff for: planning/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4747
const auto planning_test_utils_dir =
4848
ament_index_cpp::get_package_share_directory("planning_test_utils");
4949
const auto behavior_path_planner_dir =
50-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
50+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
5151

5252
std::vector<std::string> module_names;
5353

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/data_manager.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -162,7 +162,8 @@ struct PlannerData
162162
std::shared_ptr<RouteHandler> route_handler{std::make_shared<RouteHandler>()};
163163
std::map<int64_t, TrafficSignalStamped> traffic_light_id_map;
164164
BehaviorPathPlannerParameters parameters{};
165-
drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{};
165+
autoware::behavior_path_planner::drivable_area_expansion::DrivableAreaExpansionParameters
166+
drivable_area_expansion_parameters{};
166167
VelocityLimit::ConstSharedPtr external_limit_max_velocity{};
167168

168169
mutable std::vector<geometry_msgs::msg::Pose> drivable_area_expansion_prev_path_poses{};

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/drivable_area_expansion.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
#include <memory>
2727
#include <vector>
2828

29-
namespace drivable_area_expansion
29+
namespace autoware::behavior_path_planner::drivable_area_expansion
3030
{
3131
/// @brief Expand the drivable area based on the path curvature and the vehicle dimensions
3232
/// @param[inout] path path whose drivable area will be expanded
@@ -131,7 +131,7 @@ void calculate_expansion_distances(
131131
std::vector<double> calculate_smoothed_curvatures(
132132
const std::vector<Pose> & poses, const size_t smoothing_window_size);
133133

134-
} // namespace drivable_area_expansion
134+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
135135

136136
// clang-format off
137137
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__DRIVABLE_AREA_EXPANSION_HPP_ // NOLINT

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2424
#include <geometry_msgs/msg/pose.hpp>
2525

26-
namespace drivable_area_expansion
26+
namespace autoware::behavior_path_planner::drivable_area_expansion
2727
{
2828
/// @brief translate a polygon by some (x,y) vector
2929
/// @param[in] polygon input polygon
@@ -45,5 +45,5 @@ Polygon2d create_footprint(const geometry_msgs::msg::Pose & pose, const Polygon2
4545
MultiPolygon2d create_object_footprints(
4646
const autoware_perception_msgs::msg::PredictedObjects & objects,
4747
const DrivableAreaExpansionParameters & params);
48-
} // namespace drivable_area_expansion
48+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
4949
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__FOOTPRINTS_HPP_

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/map_utils.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include <string>
2424
#include <vector>
2525

26-
namespace drivable_area_expansion
26+
namespace autoware::behavior_path_planner::drivable_area_expansion
2727
{
2828
/// @brief Extract uncrossable segments from the lanelet map that are in range of ego
2929
/// @param[in] lanelet_map lanelet map
@@ -39,6 +39,6 @@ SegmentRtree extract_uncrossable_segments(
3939
/// @param[in] types type strings to check
4040
/// @return true if the linestring has one of the given types
4141
bool has_types(const lanelet::ConstLineString3d & ls, const std::vector<std::string> & types);
42-
} // namespace drivable_area_expansion
42+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
4343

4444
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__MAP_UTILS_HPP_

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#include <string>
2222
#include <vector>
2323

24-
namespace drivable_area_expansion
24+
namespace autoware::behavior_path_planner::drivable_area_expansion
2525
{
2626

2727
struct DrivableAreaExpansionParameters
@@ -125,5 +125,5 @@ struct DrivableAreaExpansionParameters
125125
}
126126
};
127127

128-
} // namespace drivable_area_expansion
128+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
129129
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323

2424
#include <limits>
2525

26-
namespace drivable_area_expansion
26+
namespace autoware::behavior_path_planner::drivable_area_expansion
2727
{
2828
/// @brief project a point to a segment
2929
/// @param p point to project on the segment
@@ -178,7 +178,7 @@ inline LineString2d sub_linestring(
178178
sub_ls.push_back(to_point);
179179
return sub_ls;
180180
}
181-
} // namespace drivable_area_expansion
181+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
182182

183183
// clang-format off
184184
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PATH_PROJECTION_HPP_ // NOLINT

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include <vector>
2424
namespace autoware::behavior_path_planner::utils
2525
{
26-
using drivable_area_expansion::DrivableAreaExpansionParameters;
26+
using autoware::behavior_path_planner::drivable_area_expansion::DrivableAreaExpansionParameters;
2727

2828
std::optional<size_t> getOverlappedLaneletId(const std::vector<DrivableLanes> & lanes);
2929

Diff for: planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/types.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
#include <optional>
2828
#include <vector>
2929

30-
namespace drivable_area_expansion
30+
namespace autoware::behavior_path_planner::drivable_area_expansion
3131
{
3232
using autoware_perception_msgs::msg::PredictedObjects;
3333
using autoware_planning_msgs::msg::PathPoint;
@@ -70,5 +70,5 @@ struct Expansion
7070
std::vector<PointDistance> right_projections;
7171
std::vector<double> min_lane_widths;
7272
};
73-
} // namespace drivable_area_expansion
73+
} // namespace autoware::behavior_path_planner::drivable_area_expansion
7474
#endif // AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__TYPES_HPP_

Diff for: planning/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030

3131
#include <limits>
3232

33-
namespace drivable_area_expansion
33+
namespace autoware::behavior_path_planner::drivable_area_expansion
3434
{
3535

3636
namespace
@@ -435,4 +435,4 @@ void expand_drivable_area(
435435
planner_data->drivable_area_expansion_prev_path_poses = path_poses;
436436
planner_data->drivable_area_expansion_prev_curvatures = curvatures;
437437
}
438-
} // namespace drivable_area_expansion
438+
} // namespace autoware::behavior_path_planner::drivable_area_expansion

Diff for: planning/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323

2424
#include <tf2/utils.h>
2525

26-
namespace drivable_area_expansion
26+
namespace autoware::behavior_path_planner::drivable_area_expansion
2727
{
2828
Polygon2d translate_polygon(const Polygon2d & polygon, const double x, const double y)
2929
{
@@ -62,4 +62,4 @@ MultiPolygon2d create_object_footprints(
6262
}
6363
return footprints;
6464
}
65-
} // namespace drivable_area_expansion
65+
} // namespace autoware::behavior_path_planner::drivable_area_expansion

Diff for: planning/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
#include <algorithm>
2323

24-
namespace drivable_area_expansion
24+
namespace autoware::behavior_path_planner::drivable_area_expansion
2525
{
2626
SegmentRtree extract_uncrossable_segments(
2727
const lanelet::LaneletMap & lanelet_map, const Point & ego_point,
@@ -51,4 +51,4 @@ bool has_types(const lanelet::ConstLineString3d & ls, const std::vector<std::str
5151
const auto type = ls.attributeOr(lanelet::AttributeName::Type, no_type);
5252
return (type != no_type && std::find(types.begin(), types.end(), type) != types.end());
5353
}
54-
} // namespace drivable_area_expansion
54+
} // namespace autoware::behavior_path_planner::drivable_area_expansion

Diff for: planning/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -843,7 +843,8 @@ void generateDrivableArea(
843843

844844
const auto & expansion_params = planner_data->drivable_area_expansion_parameters;
845845
if (expansion_params.enabled) {
846-
drivable_area_expansion::expand_drivable_area(path, planner_data);
846+
autoware::behavior_path_planner::drivable_area_expansion::expand_drivable_area(
847+
path, planner_data);
847848
}
848849
}
849850

Diff for: planning/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp

+19-17
Original file line numberDiff line numberDiff line change
@@ -21,14 +21,14 @@
2121
#include <gtest/gtest.h>
2222
#include <lanelet2_core/LaneletMap.h>
2323

24-
using drivable_area_expansion::LineString2d;
25-
using drivable_area_expansion::Point2d;
26-
using drivable_area_expansion::Segment2d;
24+
using autoware::behavior_path_planner::drivable_area_expansion::LineString2d;
25+
using autoware::behavior_path_planner::drivable_area_expansion::Point2d;
26+
using autoware::behavior_path_planner::drivable_area_expansion::Segment2d;
2727
constexpr auto eps = 1e-9;
2828

2929
TEST(DrivableAreaExpansionProjection, PointToSegment)
3030
{
31-
using drivable_area_expansion::point_to_segment_projection;
31+
using autoware::behavior_path_planner::drivable_area_expansion::point_to_segment_projection;
3232

3333
{
3434
Point2d query(1.0, 1.0);
@@ -90,7 +90,7 @@ TEST(DrivableAreaExpansionProjection, PointToSegment)
9090

9191
TEST(DrivableAreaExpansionProjection, PointToLinestring)
9292
{
93-
using drivable_area_expansion::point_to_linestring_projection;
93+
using autoware::behavior_path_planner::drivable_area_expansion::point_to_linestring_projection;
9494

9595
LineString2d ls = {
9696
Point2d(0.0, 0.0), Point2d(10.0, 0.0), Point2d(10.0, 10.0), Point2d(0.0, 10.0),
@@ -123,7 +123,7 @@ TEST(DrivableAreaExpansionProjection, PointToLinestring)
123123

124124
TEST(DrivableAreaExpansionProjection, LinestringToPoint)
125125
{
126-
using drivable_area_expansion::linestring_to_point_projection;
126+
using autoware::behavior_path_planner::drivable_area_expansion::linestring_to_point_projection;
127127

128128
LineString2d ls = {
129129
Point2d(0.0, 0.0), Point2d(10.0, 0.0), Point2d(10.0, 10.0), Point2d(0.0, 10.0),
@@ -153,8 +153,8 @@ TEST(DrivableAreaExpansionProjection, LinestringToPoint)
153153

154154
TEST(DrivableAreaExpansionProjection, InverseProjection)
155155
{
156-
using drivable_area_expansion::linestring_to_point_projection;
157-
using drivable_area_expansion::point_to_linestring_projection;
156+
using autoware::behavior_path_planner::drivable_area_expansion::linestring_to_point_projection;
157+
using autoware::behavior_path_planner::drivable_area_expansion::point_to_linestring_projection;
158158

159159
LineString2d ls = {
160160
Point2d(0.0, 0.0), Point2d(10.0, 0.0), Point2d(10.0, 10.0), Point2d(0.0, 10.0),
@@ -174,16 +174,17 @@ TEST(DrivableAreaExpansionProjection, InverseProjection)
174174

175175
TEST(DrivableAreaExpansionProjection, expand_drivable_area)
176176
{
177-
drivable_area_expansion::DrivableAreaExpansionParameters params;
178-
drivable_area_expansion::PredictedObjects dynamic_objects;
177+
autoware::behavior_path_planner::drivable_area_expansion::DrivableAreaExpansionParameters params;
178+
autoware::behavior_path_planner::drivable_area_expansion::PredictedObjects dynamic_objects;
179179
autoware_map_msgs::msg::LaneletMapBin map;
180180
lanelet::LaneletMapPtr empty_lanelet_map_ptr = std::make_shared<lanelet::LaneletMap>();
181181
lanelet::utils::conversion::toBinMsg(empty_lanelet_map_ptr, &map);
182182
autoware::route_handler::RouteHandler route_handler(map);
183183
lanelet::ConstLanelets path_lanes = {};
184-
drivable_area_expansion::PathWithLaneId path;
184+
autoware::behavior_path_planner::drivable_area_expansion::PathWithLaneId path;
185185
{ // Simple path with Y=0 and X = 0, 1, 2
186-
drivable_area_expansion::PathWithLaneId::_points_type::value_type p;
186+
autoware::behavior_path_planner::drivable_area_expansion::PathWithLaneId::_points_type::
187+
value_type p;
187188
p.point.pose.position.x = 0.0;
188189
p.point.pose.position.y = 0.0;
189190
path.points.push_back(p);
@@ -193,8 +194,8 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
193194
path.points.push_back(p);
194195
}
195196
{ // Left bound at Y = 1, Right bound at Y = -1
196-
drivable_area_expansion::Point pl;
197-
drivable_area_expansion::Point pr;
197+
autoware::behavior_path_planner::drivable_area_expansion::Point pl;
198+
autoware::behavior_path_planner::drivable_area_expansion::Point pr;
198199
pl.y = 1.0;
199200
pr.y = -1.0;
200201
pl.x = 0.0;
@@ -226,11 +227,12 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
226227
autoware::behavior_path_planner::PlannerData planner_data;
227228
planner_data.drivable_area_expansion_parameters = params;
228229
planner_data.dynamic_object =
229-
std::make_shared<drivable_area_expansion::PredictedObjects>(dynamic_objects);
230+
std::make_shared<autoware::behavior_path_planner::drivable_area_expansion::PredictedObjects>(
231+
dynamic_objects);
230232
planner_data.self_odometry = std::make_shared<nav_msgs::msg::Odometry>();
231233
planner_data.route_handler =
232234
std::make_shared<autoware::route_handler::RouteHandler>(route_handler);
233-
drivable_area_expansion::expand_drivable_area(
235+
autoware::behavior_path_planner::drivable_area_expansion::expand_drivable_area(
234236
path, std::make_shared<autoware::behavior_path_planner::PlannerData>(planner_data));
235237
// unchanged path points
236238
ASSERT_EQ(path.points.size(), 3ul);
@@ -259,7 +261,7 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
259261
// add some curvature
260262
path.points[1].point.pose.position.y = 0.5;
261263

262-
drivable_area_expansion::expand_drivable_area(
264+
autoware::behavior_path_planner::drivable_area_expansion::expand_drivable_area(
263265
path, std::make_shared<autoware::behavior_path_planner::PlannerData>(planner_data));
264266
// expanded left bound
265267
ASSERT_EQ(path.left_bound.size(), 3ul);

Diff for: planning/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4747
const auto planning_test_utils_dir =
4848
ament_index_cpp::get_package_share_directory("planning_test_utils");
4949
const auto behavior_path_planner_dir =
50-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
50+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
5151

5252
std::vector<std::string> module_names;
5353
module_names.emplace_back("autoware::behavior_path_planner::SideShiftModuleManager");

Diff for: planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ std::shared_ptr<BehaviorPathPlannerNode> generateNode()
4444
const auto planning_test_utils_dir =
4545
ament_index_cpp::get_package_share_directory("planning_test_utils");
4646
const auto behavior_path_planner_dir =
47-
ament_index_cpp::get_package_share_directory("behavior_path_planner");
47+
ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner");
4848

4949
std::vector<std::string> module_names;
5050
module_names.emplace_back(

0 commit comments

Comments
 (0)