Skip to content

Commit bc764cf

Browse files
committed
test(blind_spot): add unit tests
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 9f3e7a0 commit bc764cf

File tree

13 files changed

+5829
-73
lines changed

13 files changed

+5829
-73
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt

+17-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
cmake_minimum_required(VERSION 3.14)
22
project(autoware_behavior_velocity_blind_spot_module)
33

4+
option(EXPORT_TEST_PLOT_FIGURE "Export plot figures in test" OFF)
5+
46
find_package(autoware_cmake REQUIRED)
57
autoware_package()
68
pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml)
@@ -11,6 +13,20 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
1113
src/scene.cpp
1214
src/decisions.cpp
1315
src/util.cpp
16+
src/parameter.cpp
1417
)
1518

16-
ament_auto_package(INSTALL_TO_SHARE config)
19+
if(BUILD_TESTING)
20+
if(EXPORT_TEST_PLOT_FIGURE)
21+
add_definitions(-DEXPORT_TEST_PLOT_FIGURE "-Wno-attributes") # // cspell: ignore DEXPORT
22+
endif()
23+
find_package(ament_lint_auto REQUIRED)
24+
ament_lint_auto_find_test_dependencies()
25+
# NOTE(soblin): pybind11::scoped_interpreter needs to be initialized globally, not in the FixtureClass instantiated for each test suite
26+
ament_add_gtest(test_${PROJECT_NAME}_util
27+
test/test_util.cpp
28+
)
29+
target_link_libraries(test_${PROJECT_NAME}_util ${PROJECT_NAME})
30+
endif()
31+
32+
ament_auto_package(INSTALL_TO_SHARE config test_data)

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_
1616
#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_
1717

18+
#include "autoware/behavior_velocity_blind_spot_module/parameter.hpp"
1819
#include "autoware/behavior_velocity_blind_spot_module/scene.hpp"
1920

2021
#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
@@ -38,7 +39,7 @@ class BlindSpotModuleManager : public SceneModuleManagerInterfaceWithRTC
3839
const char * getModuleName() override { return "blind_spot"; }
3940

4041
private:
41-
BlindSpotModule::PlannerParam planner_param_;
42+
PlannerParam planner_param_;
4243

4344
void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
4445

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_
16+
#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_
17+
18+
#include <rclcpp/node.hpp>
19+
20+
#include <string>
21+
22+
namespace autoware::behavior_velocity_planner
23+
{
24+
struct PlannerParam
25+
{
26+
static PlannerParam init(rclcpp::Node & node, const std::string & ns);
27+
bool use_pass_judge_line{};
28+
double stop_line_margin{};
29+
double backward_detection_length{};
30+
double ignore_width_from_center_line{};
31+
double adjacent_extend_width{};
32+
double opposite_adjacent_extend_width{};
33+
double max_future_movement_time{};
34+
double ttc_min{};
35+
double ttc_max{};
36+
double ttc_ego_minimal_velocity{};
37+
};
38+
} // namespace autoware::behavior_velocity_planner
39+
40+
#endif // AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp

+1-14
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_
1616
#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_
1717

18+
#include <autoware/behavior_velocity_blind_spot_module/parameter.hpp>
1819
#include <autoware/behavior_velocity_blind_spot_module/util.hpp>
1920
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
2021
#include <autoware/behavior_velocity_planner_common/utilization/state_machine.hpp>
@@ -70,20 +71,6 @@ class BlindSpotModule : public SceneModuleInterface
7071
};
7172

7273
public:
73-
struct PlannerParam
74-
{
75-
bool use_pass_judge_line;
76-
double stop_line_margin;
77-
double backward_detection_length;
78-
double ignore_width_from_center_line;
79-
double adjacent_extend_width;
80-
double opposite_adjacent_extend_width;
81-
double max_future_movement_time;
82-
double ttc_min;
83-
double ttc_max;
84-
double ttc_ego_minimal_velocity;
85-
};
86-
8774
BlindSpotModule(
8875
const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction,
8976
const std::shared_ptr<const PlannerData> planner_data, const PlannerParam & planner_param,

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp

+26-6
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__UTIL_HPP_
1717

1818
#include <autoware/route_handler/route_handler.hpp>
19+
#include <autoware/universe_utils/geometry/geometry.hpp>
1920

2021
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
2122

@@ -25,6 +26,7 @@
2526
#include <memory>
2627
#include <optional>
2728
#include <utility>
29+
#include <vector>
2830

2931
namespace autoware::behavior_velocity_planner
3032
{
@@ -50,31 +52,49 @@ std::optional<InterpolatedPathInfo> generateInterpolatedPathInfo(
5052
const lanelet::Id lane_id, const tier4_planning_msgs::msg::PathWithLaneId & input_path,
5153
rclcpp::Logger logger);
5254

55+
std::optional<size_t> getFirstPointIntersectsLineByFootprint(
56+
const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info,
57+
const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length);
58+
5359
std::optional<lanelet::ConstLanelet> getSiblingStraightLanelet(
5460
const lanelet::Lanelet assigned_lane,
5561
const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr);
5662

5763
/**
58-
* @brief Create half lanelet
59-
* @param lanelet input lanelet
60-
* @return Half lanelet
64+
* @brief generate a new lanelet object on the `turn_direction` side of `lanelet` which is offset
65+
* from `ignore_width_from_centerline` from the centerline of `lanelet`
66+
* @return new lanelet object
6167
*/
6268
lanelet::ConstLanelet generateHalfLanelet(
6369
const lanelet::ConstLanelet lanelet, const TurnDirection & turn_direction,
6470
const double ignore_width_from_centerline);
6571

72+
/**
73+
* @brief generate a new lanelet object from the `turn_direction` side neighbouring lanelet of the
74+
* input `lanelet` by the width of `adjacent_extend_width`
75+
* @param new lanelet object
76+
*/
6677
lanelet::ConstLanelet generateExtendedAdjacentLanelet(
6778
const lanelet::ConstLanelet lanelet, const TurnDirection direction,
6879
const double adjacent_extend_width);
80+
81+
/**
82+
* @brief generate a new lanelet object from the `turn_direction` side neighbouring opposite lanelet
83+
* of the input `lanelet` by the width of `opposite_adjacent_extend_width`
84+
* @param new lanelet object
85+
*/
6986
lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet(
7087
const lanelet::ConstLanelet lanelet, const TurnDirection direction,
7188
const double opposite_adjacent_extend_width);
7289

90+
std::vector<lanelet::Id> find_lane_ids_upto(
91+
const tier4_planning_msgs::msg::PathWithLaneId & path, const lanelet::Id lane_id);
92+
7393
lanelet::ConstLanelets generateBlindSpotLanelets(
7494
const std::shared_ptr<autoware::route_handler::RouteHandler> route_handler,
75-
const TurnDirection turn_direction, const lanelet::Id lane_id,
76-
const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline,
77-
const double adjacent_extend_width, const double opposite_adjacent_extend_width);
95+
const TurnDirection turn_direction, const std::vector<lanelet::Id> lane_ids_upto_intersection,
96+
const double ignore_width_from_centerline, const double adjacent_extend_width,
97+
const double opposite_adjacent_extend_width);
7898

7999
/**
80100
* @brief Make blind spot areas. Narrow area is made from closest path point to stop line index.

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<depend>autoware_perception_msgs</depend>
2424
<depend>autoware_planning_msgs</depend>
2525
<depend>autoware_route_handler</depend>
26+
<depend>autoware_test_utils</depend>
2627
<depend>autoware_universe_utils</depend>
2728
<depend>geometry_msgs</depend>
2829
<depend>pluginlib</depend>
@@ -31,6 +32,7 @@
3132
<depend>tier4_planning_msgs</depend>
3233
<depend>visualization_msgs</depend>
3334

35+
<test_depend>ament_cmake_ros</test_depend>
3436
<test_depend>ament_lint_auto</test_depend>
3537
<test_depend>autoware_lint_common</test_depend>
3638

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp

+1-17
Original file line numberDiff line numberDiff line change
@@ -34,23 +34,7 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
3434
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
3535
{
3636
const std::string ns(BlindSpotModuleManager::getModuleName());
37-
planner_param_.use_pass_judge_line =
38-
getOrDeclareParameter<bool>(node, ns + ".use_pass_judge_line");
39-
planner_param_.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".stop_line_margin");
40-
planner_param_.backward_detection_length =
41-
getOrDeclareParameter<double>(node, ns + ".backward_detection_length");
42-
planner_param_.ignore_width_from_center_line =
43-
getOrDeclareParameter<double>(node, ns + ".ignore_width_from_center_line");
44-
planner_param_.adjacent_extend_width =
45-
getOrDeclareParameter<double>(node, ns + ".adjacent_extend_width");
46-
planner_param_.opposite_adjacent_extend_width =
47-
getOrDeclareParameter<double>(node, ns + ".opposite_adjacent_extend_width");
48-
planner_param_.max_future_movement_time =
49-
getOrDeclareParameter<double>(node, ns + ".max_future_movement_time");
50-
planner_param_.ttc_min = getOrDeclareParameter<double>(node, ns + ".ttc_min");
51-
planner_param_.ttc_max = getOrDeclareParameter<double>(node, ns + ".ttc_max");
52-
planner_param_.ttc_ego_minimal_velocity =
53-
getOrDeclareParameter<double>(node, ns + ".ttc_ego_minimal_velocity");
37+
planner_param_ = PlannerParam::init(node, ns);
5438
}
5539

5640
void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "autoware/behavior_velocity_blind_spot_module/parameter.hpp"
16+
17+
#include <autoware/universe_utils/ros/parameter.hpp>
18+
19+
#include <string>
20+
21+
namespace autoware::behavior_velocity_planner
22+
{
23+
24+
PlannerParam PlannerParam::init(rclcpp::Node & node, const std::string & ns)
25+
{
26+
using autoware::universe_utils::getOrDeclareParameter;
27+
PlannerParam param;
28+
param.use_pass_judge_line = getOrDeclareParameter<bool>(node, ns + ".use_pass_judge_line");
29+
param.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".stop_line_margin");
30+
param.backward_detection_length =
31+
getOrDeclareParameter<double>(node, ns + ".backward_detection_length");
32+
param.ignore_width_from_center_line =
33+
getOrDeclareParameter<double>(node, ns + ".ignore_width_from_center_line");
34+
param.adjacent_extend_width = getOrDeclareParameter<double>(node, ns + ".adjacent_extend_width");
35+
param.opposite_adjacent_extend_width =
36+
getOrDeclareParameter<double>(node, ns + ".opposite_adjacent_extend_width");
37+
param.max_future_movement_time =
38+
getOrDeclareParameter<double>(node, ns + ".max_future_movement_time");
39+
param.ttc_min = getOrDeclareParameter<double>(node, ns + ".ttc_min");
40+
param.ttc_max = getOrDeclareParameter<double>(node, ns + ".ttc_max");
41+
param.ttc_ego_minimal_velocity =
42+
getOrDeclareParameter<double>(node, ns + ".ttc_ego_minimal_velocity");
43+
return param;
44+
}
45+
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp

+2-22
Original file line numberDiff line numberDiff line change
@@ -101,8 +101,9 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * pat
101101
}
102102

103103
if (!blind_spot_lanelets_) {
104+
const auto lane_ids_upto_intersection = find_lane_ids_upto(input_path, lane_id_);
104105
const auto blind_spot_lanelets = generateBlindSpotLanelets(
105-
planner_data_->route_handler_, turn_direction_, lane_id_, input_path,
106+
planner_data_->route_handler_, turn_direction_, lane_ids_upto_intersection,
106107
planner_param_.ignore_width_from_center_line, planner_param_.adjacent_extend_width,
107108
planner_param_.opposite_adjacent_extend_width);
108109
if (!blind_spot_lanelets.empty()) {
@@ -179,27 +180,6 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path)
179180
return true;
180181
}
181182

182-
static std::optional<size_t> getFirstPointIntersectsLineByFootprint(
183-
const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info,
184-
const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length)
185-
{
186-
const auto & path_ip = interpolated_path_info.path;
187-
const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value();
188-
const size_t vehicle_length_idx = static_cast<size_t>(vehicle_length / interpolated_path_info.ds);
189-
const size_t start =
190-
static_cast<size_t>(std::max<int>(0, static_cast<int>(lane_start) - vehicle_length_idx));
191-
const auto line2d = line.basicLineString();
192-
for (auto i = start; i <= lane_end; ++i) {
193-
const auto & base_pose = path_ip.points.at(i).point.pose;
194-
const auto path_footprint = autoware::universe_utils::transformVector(
195-
footprint, autoware::universe_utils::pose2transform(base_pose));
196-
if (bg::intersects(path_footprint, line2d)) {
197-
return std::make_optional<size_t>(i);
198-
}
199-
}
200-
return std::nullopt;
201-
}
202-
203183
static std::optional<size_t> getDuplicatedPointIdx(
204184
const tier4_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & point)
205185
{

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp

+37-12
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,27 @@ std::optional<InterpolatedPathInfo> generateInterpolatedPathInfo(
8888
return interpolated_path_info;
8989
}
9090

91+
std::optional<size_t> getFirstPointIntersectsLineByFootprint(
92+
const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info,
93+
const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length)
94+
{
95+
const auto & path_ip = interpolated_path_info.path;
96+
const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value();
97+
const size_t vehicle_length_idx = static_cast<size_t>(vehicle_length / interpolated_path_info.ds);
98+
const size_t start =
99+
static_cast<size_t>(std::max<int>(0, static_cast<int>(lane_start) - vehicle_length_idx));
100+
const auto line2d = line.basicLineString();
101+
for (auto i = start; i <= lane_end; ++i) {
102+
const auto & base_pose = path_ip.points.at(i).point.pose;
103+
const auto path_footprint = autoware::universe_utils::transformVector(
104+
footprint, autoware::universe_utils::pose2transform(base_pose));
105+
if (boost::geometry::intersects(path_footprint, line2d)) {
106+
return std::make_optional<size_t>(i);
107+
}
108+
}
109+
return std::nullopt;
110+
}
111+
91112
std::optional<lanelet::ConstLanelet> getSiblingStraightLanelet(
92113
const lanelet::Lanelet assigned_lane,
93114
const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr)
@@ -200,35 +221,39 @@ static lanelet::LineString3d removeConst(lanelet::ConstLineString3d line)
200221
return lanelet::LineString3d(lanelet::InvalId, pts);
201222
}
202223

203-
lanelet::ConstLanelets generateBlindSpotLanelets(
204-
const std::shared_ptr<autoware::route_handler::RouteHandler> route_handler,
205-
const TurnDirection turn_direction, const lanelet::Id lane_id,
206-
const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline,
207-
const double adjacent_extend_width, const double opposite_adjacent_extend_width)
224+
std::vector<lanelet::Id> find_lane_ids_upto(
225+
const tier4_planning_msgs::msg::PathWithLaneId & path, const lanelet::Id lane_id)
208226
{
209-
const auto lanelet_map_ptr = route_handler->getLaneletMapPtr();
210-
const auto routing_graph_ptr = route_handler->getRoutingGraphPtr();
211-
212227
std::vector<int64_t> lane_ids;
213228
/* get lane ids until intersection */
214229
for (const auto & point : path.points) {
215230
bool found_intersection_lane = false;
216231
for (const auto id : point.lane_ids) {
217232
if (id == lane_id) {
218233
found_intersection_lane = true;
219-
lane_ids.push_back(lane_id);
220234
break;
221235
}
222236
// make lane_ids unique
223-
if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) {
224-
lane_ids.push_back(lane_id);
237+
if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) {
238+
lane_ids.push_back(id);
225239
}
226240
}
227241
if (found_intersection_lane) break;
228242
}
243+
return lane_ids;
244+
}
245+
246+
lanelet::ConstLanelets generateBlindSpotLanelets(
247+
const std::shared_ptr<autoware::route_handler::RouteHandler> route_handler,
248+
const TurnDirection turn_direction, const std::vector<lanelet::Id> lane_ids_upto_intersection,
249+
const double ignore_width_from_centerline, const double adjacent_extend_width,
250+
const double opposite_adjacent_extend_width)
251+
{
252+
const auto lanelet_map_ptr = route_handler->getLaneletMapPtr();
253+
const auto routing_graph_ptr = route_handler->getRoutingGraphPtr();
229254

230255
lanelet::ConstLanelets blind_spot_lanelets;
231-
for (const auto i : lane_ids) {
256+
for (const auto i : lane_ids_upto_intersection) {
232257
const auto lane = lanelet_map_ptr->laneletLayer.get(i);
233258
const auto ego_half_lanelet =
234259
generateHalfLanelet(lane, turn_direction, ignore_width_from_centerline);

0 commit comments

Comments
 (0)