Skip to content

Commit 962a81e

Browse files
Merge pull request #1064 from kyoichi-sugahara/beta/v0.18.0+PR5792
fix(start_planner): check safety only when waiting approval (autowarefoundation#5792)
2 parents b96b339 + ca5cf61 commit 962a81e

File tree

7 files changed

+121
-6
lines changed

7 files changed

+121
-6
lines changed

planning/behavior_path_planner/config/start_planner/start_planner.param.yaml

+14
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,20 @@
138138
backward_path_length: 30.0
139139
forward_path_length: 100.0
140140

141+
surround_moving_obstacle_check:
142+
search_radius: 10.0
143+
th_moving_obstacle_velocity: 1.0
144+
# ObjectTypesToCheck
145+
object_types_to_check:
146+
check_car: true
147+
check_truck: true
148+
check_bus: true
149+
check_trailer: true
150+
check_bicycle: true
151+
check_motorcycle: true
152+
check_pedestrian: true
153+
check_unknown: false
154+
141155
# debug
142156
debug:
143157
print_debug_info: false

planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp

+11
Original file line numberDiff line numberDiff line change
@@ -137,6 +137,17 @@ class StartPlannerModule : public SceneModuleInterface
137137
void initializeSafetyCheckParameters();
138138

139139
bool requiresDynamicObjectsCollisionDetection() const;
140+
141+
/**
142+
* @brief Check if there are no moving objects around within a certain radius.
143+
*
144+
* This function filters the dynamic objects within a certain radius and then filters them by
145+
* their velocity. If there are no moving objects around, it returns true. Otherwise, it returns
146+
* false.
147+
*
148+
* @return True if there are no moving objects around. False otherwise.
149+
*/
150+
bool noMovingObjectsAround() const;
140151
bool receivedNewRoute() const;
141152

142153
bool isModuleRunning() const;

planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,12 @@ struct StartPlannerParameters
9393
utils::path_safety_checker::ObjectsFilteringParams objects_filtering_params{};
9494
utils::path_safety_checker::SafetyCheckParams safety_check_params{};
9595

96+
// surround moving obstacle check
97+
double search_radius{0.0};
98+
double th_moving_obstacle_velocity{0.0};
99+
behavior_path_planner::utils::path_safety_checker::ObjectTypesToCheck
100+
surround_moving_obstacles_type_to_check{};
101+
96102
bool print_debug_info{false};
97103
};
98104

planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp

+29
Original file line numberDiff line numberDiff line change
@@ -273,6 +273,35 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
273273
node->declare_parameter<double>(rss_ns + "longitudinal_velocity_delta_time");
274274
}
275275

276+
// surround moving obstacle check
277+
std::string surround_moving_obstacle_check_ns = ns + "surround_moving_obstacle_check.";
278+
{
279+
p.search_radius =
280+
node->declare_parameter<double>(surround_moving_obstacle_check_ns + "search_radius");
281+
p.th_moving_obstacle_velocity = node->declare_parameter<double>(
282+
surround_moving_obstacle_check_ns + "th_moving_obstacle_velocity");
283+
// ObjectTypesToCheck
284+
std::string obj_types_ns = surround_moving_obstacle_check_ns + "object_types_to_check.";
285+
{
286+
p.surround_moving_obstacles_type_to_check.check_car =
287+
node->declare_parameter<bool>(obj_types_ns + "check_car");
288+
p.surround_moving_obstacles_type_to_check.check_truck =
289+
node->declare_parameter<bool>(obj_types_ns + "check_truck");
290+
p.surround_moving_obstacles_type_to_check.check_bus =
291+
node->declare_parameter<bool>(obj_types_ns + "check_bus");
292+
p.surround_moving_obstacles_type_to_check.check_trailer =
293+
node->declare_parameter<bool>(obj_types_ns + "check_trailer");
294+
p.surround_moving_obstacles_type_to_check.check_unknown =
295+
node->declare_parameter<bool>(obj_types_ns + "check_unknown");
296+
p.surround_moving_obstacles_type_to_check.check_bicycle =
297+
node->declare_parameter<bool>(obj_types_ns + "check_bicycle");
298+
p.surround_moving_obstacles_type_to_check.check_motorcycle =
299+
node->declare_parameter<bool>(obj_types_ns + "check_motorcycle");
300+
p.surround_moving_obstacles_type_to_check.check_pedestrian =
301+
node->declare_parameter<bool>(obj_types_ns + "check_pedestrian");
302+
}
303+
}
304+
276305
// debug
277306
std::string debug_ns = ns + "debug.";
278307
{

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

+27-6
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,8 @@ void StartPlannerModule::updateData()
146146

147147
if (requiresDynamicObjectsCollisionDetection()) {
148148
status_.is_safe_dynamic_objects = !hasCollisionWithDynamicObjects();
149+
} else {
150+
status_.is_safe_dynamic_objects = true;
149151
}
150152
}
151153

@@ -179,6 +181,21 @@ bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const
179181
return parameters_->safety_check_params.enable_safety_check && status_.driving_forward;
180182
}
181183

184+
bool StartPlannerModule::noMovingObjectsAround() const
185+
{
186+
auto dynamic_objects = *(planner_data_->dynamic_object);
187+
utils::path_safety_checker::filterObjectsWithinRadius(
188+
dynamic_objects, planner_data_->self_odometry->pose.pose.position, parameters_->search_radius);
189+
utils::path_safety_checker::filterObjectsByClass(
190+
dynamic_objects, parameters_->surround_moving_obstacles_type_to_check);
191+
const auto filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
192+
dynamic_objects, parameters_->th_moving_obstacle_velocity, false);
193+
if (!filtered_objects.objects.empty()) {
194+
DEBUG_PRINT("Moving objects exist in the safety check area");
195+
}
196+
return filtered_objects.objects.empty();
197+
}
198+
182199
bool StartPlannerModule::hasCollisionWithDynamicObjects() const
183200
{
184201
// TODO(Sugahara): update path, params for predicted path and so on in this function to avoid
@@ -271,20 +288,24 @@ bool StartPlannerModule::isStopped()
271288
bool StartPlannerModule::isExecutionReady() const
272289
{
273290
bool is_safe = true;
274-
275291
// Evaluate safety. The situation is not safe if any of the following conditions are met:
276292
// 1. pull out path has not been found
277-
// 2. waiting for approval and there is a collision with dynamic objects
293+
// 2. there is a moving objects around ego
294+
// 3. waiting for approval and there is a collision with dynamic objects
278295
if (!status_.found_pull_out_path) {
279296
is_safe = false;
297+
} else if (isWaitingApproval()) {
298+
if (!noMovingObjectsAround()) {
299+
is_safe = false;
300+
} else if (requiresDynamicObjectsCollisionDetection() && hasCollisionWithDynamicObjects()) {
301+
is_safe = false;
302+
}
280303
}
281304

282-
if (requiresDynamicObjectsCollisionDetection()) {
283-
is_safe = !hasCollisionWithDynamicObjects();
305+
if (!is_safe) {
306+
stop_pose_ = planner_data_->self_odometry->pose.pose;
284307
}
285308

286-
if (!is_safe) stop_pose_ = planner_data_->self_odometry->pose.pose;
287-
288309
return is_safe;
289310
}
290311

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp

+13
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,19 @@ void filterObjectsByPosition(
134134
const geometry_msgs::msg::Point & current_pose, const double forward_distance,
135135
const double backward_distance);
136136

137+
/**
138+
* @brief Filter objects based on their distance from a reference point.
139+
*
140+
* This function filters out objects that are outside a specified radius from a reference point.
141+
*
142+
* @param objects The predicted objects to filter.
143+
* @param reference_point The reference point (e.g., current pose of the ego vehicle).
144+
* @param search_radius The radius within which to retain objects.
145+
*/
146+
void filterObjectsWithinRadius(
147+
PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point,
148+
const double search_radius);
149+
137150
/**
138151
* @brief Filters the provided objects based on their classification.
139152
*

planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

+21
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,15 @@ bool position_filter(
4444

4545
return (backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance);
4646
}
47+
48+
bool is_within_circle(
49+
const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point,
50+
const double search_radius)
51+
{
52+
const double dist =
53+
std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y);
54+
return dist < search_radius;
55+
}
4756
} // namespace behavior_path_planner::utils::path_safety_checker::filter
4857

4958
namespace behavior_path_planner::utils::path_safety_checker
@@ -128,6 +137,18 @@ void filterObjectsByPosition(
128137
filterObjects(objects, filter);
129138
}
130139

140+
void filterObjectsWithinRadius(
141+
PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point,
142+
const double search_radius)
143+
{
144+
const auto filter = [&](const auto & object) {
145+
return filter::is_within_circle(
146+
object.kinematics.initial_pose_with_covariance.pose.position, reference_point, search_radius);
147+
};
148+
149+
filterObjects(objects, filter);
150+
}
151+
131152
void filterObjectsByClass(
132153
PredictedObjects & objects, const ObjectTypesToCheck & target_object_types)
133154
{

0 commit comments

Comments
 (0)