16
16
17
17
#include " motion_utils/resample/resample.hpp"
18
18
#include " motion_utils/trajectory/tmp_conversion.hpp"
19
+ #include " motion_utils/trajectory/trajectory.hpp"
19
20
#include " object_recognition_utils/predicted_path_utils.hpp"
20
21
#include " obstacle_cruise_planner/polygon_utils.hpp"
21
22
#include " obstacle_cruise_planner/utils.hpp"
22
23
#include " tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
23
24
#include " tier4_autoware_utils/ros/marker_helper.hpp"
24
25
#include " tier4_autoware_utils/ros/update_param.hpp"
25
26
27
+ #include < lanelet2_extension/utility/message_conversion.hpp>
28
+ #include < lanelet2_extension/utility/query.hpp>
29
+ #include < lanelet2_extension/utility/utilities.hpp>
30
+
26
31
#include < boost/format.hpp>
32
+ #include < boost/geometry/algorithms/intersects.hpp>
33
+ #include < boost/geometry/algorithms/within.hpp>
34
+
35
+ #include < lanelet2_core/geometry/LineString.h>
36
+ #include < lanelet2_core/geometry/Polygon.h>
27
37
28
38
#include < algorithm>
29
39
#include < chrono>
@@ -275,6 +285,14 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
275
285
" behavior_determination.consider_current_pose.enable_to_consider_current_pose" );
276
286
time_to_convergence = node.declare_parameter <double >(
277
287
" behavior_determination.consider_current_pose.time_to_convergence" );
288
+ work_as_pseudo_occlusion = node.declare_parameter <bool >(
289
+ " behavior_determination.slow_down.pseudo_occlusion.enable_function" );
290
+ if (work_as_pseudo_occlusion) {
291
+ max_obj_vel_for_pseudo_occlusion = node.declare_parameter <double >(
292
+ " behavior_determination.slow_down.pseudo_occlusion.max_obj_vel" );
293
+ focus_intersections_for_pseudo_occlusion = node.declare_parameter <std::vector<lanelet::Id>>(
294
+ " behavior_determination.slow_down.pseudo_occlusion.focus_intersections" );
295
+ }
278
296
}
279
297
280
298
void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam (
@@ -335,6 +353,17 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
335
353
tier4_autoware_utils::updateParam<double >(
336
354
parameters, " behavior_determination.consider_current_pose.time_to_convergence" ,
337
355
time_to_convergence);
356
+ tier4_autoware_utils::updateParam<bool >(
357
+ parameters, " behavior_determination.slow_down.pseudo_occlusion.enable_function" ,
358
+ work_as_pseudo_occlusion);
359
+ if (work_as_pseudo_occlusion) {
360
+ tier4_autoware_utils::updateParam<double >(
361
+ parameters, " behavior_determination.slow_down.pseudo_occlusion.max_obj_vel" ,
362
+ max_obj_vel_for_pseudo_occlusion);
363
+ tier4_autoware_utils::updateParam<std::vector<lanelet::Id>>(
364
+ parameters, " behavior_determination.slow_down.pseudo_occlusion.focus_intersections" ,
365
+ focus_intersections_for_pseudo_occlusion);
366
+ }
338
367
}
339
368
340
369
ObstacleCruisePlannerNode::ObstacleCruisePlannerNode (const rclcpp::NodeOptions & node_options)
@@ -357,6 +386,9 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions &
357
386
acc_sub_ = create_subscription<AccelWithCovarianceStamped>(
358
387
" ~/input/acceleration" , rclcpp::QoS{1 },
359
388
[this ](const AccelWithCovarianceStamped::ConstSharedPtr msg) { ego_accel_ptr_ = msg; });
389
+ lanelet_map_sub_ = create_subscription<HADMapBin>(
390
+ " ~/input/vector_map" , rclcpp::QoS (10 ).transient_local (),
391
+ [this ](const HADMapBin::ConstSharedPtr msg) { vector_map_ptr_ = msg; });
360
392
361
393
// publisher
362
394
trajectory_pub_ = create_publisher<Trajectory>(" ~/output/trajectory" , 1 );
@@ -483,14 +515,18 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam(
483
515
484
516
void ObstacleCruisePlannerNode::onTrajectory (const Trajectory::ConstSharedPtr msg)
485
517
{
518
+ stop_watch_.tic (__func__);
486
519
const auto traj_points = motion_utils::convertToTrajectoryPointArray (*msg);
487
520
488
521
// check if subscribed variables are ready
489
- if (traj_points.empty () || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_) {
522
+ if (
523
+ traj_points.empty () || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_ || !vector_map_ptr_) {
490
524
return ;
491
525
}
526
+ if (route_handler_ == nullptr ) {
527
+ route_handler_ = std::make_unique<route_handler::RouteHandler>(*vector_map_ptr_);
528
+ }
492
529
493
- stop_watch_.tic (__func__);
494
530
*debug_data_ptr_ = DebugData ();
495
531
496
532
const auto is_driving_forward = motion_utils::isDrivingForwardWithTwist (traj_points);
@@ -1130,6 +1166,37 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
1130
1166
return std::nullopt;
1131
1167
}
1132
1168
1169
+ const auto is_occlusion_object = [&]() {
1170
+ if (
1171
+ std::hypot (obstacle.twist .linear .x , obstacle.twist .linear .y ) >
1172
+ behavior_determination_param_.max_obj_vel_for_pseudo_occlusion + 1e-6 ) {
1173
+ return false ;
1174
+ }
1175
+
1176
+ if (motion_utils::calcLateralOffset (traj_points, obstacle.pose .position ) > 0.0 ) {
1177
+ return true ;
1178
+ }
1179
+
1180
+ for (const auto & id : behavior_determination_param_.focus_intersections_for_pseudo_occlusion ) {
1181
+ if (id == 0 ) {
1182
+ continue ;
1183
+ }
1184
+ const auto intersection_poly =
1185
+ lanelet::utils::to2D (route_handler_->getLaneletMapPtr ()->polygonLayer .get (id))
1186
+ .basicPolygon ();
1187
+ if (
1188
+ boost::geometry::within (obstacle_poly, intersection_poly) ||
1189
+ boost::geometry::intersects (obstacle_poly, intersection_poly)) {
1190
+ return true ;
1191
+ }
1192
+ }
1193
+ return false ;
1194
+ };
1195
+
1196
+ if (behavior_determination_param_.work_as_pseudo_occlusion && !is_occlusion_object ()) {
1197
+ return std::nullopt;
1198
+ }
1199
+
1133
1200
// calculate front collision point
1134
1201
double front_min_dist = std::numeric_limits<double >::max ();
1135
1202
geometry_msgs::msg::Point front_collision_point;
0 commit comments